일 | 월 | 화 | 수 | 목 | 금 | 토 |
---|---|---|---|---|---|---|
1 | 2 | 3 | 4 | 5 | 6 | 7 |
8 | 9 | 10 | 11 | 12 | 13 | 14 |
15 | 16 | 17 | 18 | 19 | 20 | 21 |
22 | 23 | 24 | 25 | 26 | 27 | 28 |
29 | 30 | 31 |
- pandas
- 카트폴
- App
- Instagrame clone
- clone coding
- python
- ReactNative
- 전국국밥
- 데이터분석
- expo
- React
- JavaScript
- kaggle
- 정치인
- coding
- 사이드프로젝트
- 딥러닝
- Ros
- 앱개발
- TeachagleMachine
- 조코딩
- 강화학습 기초
- redux
- selenium
- 클론코딩
- 리액트네이티브
- 크롤링
- 머신러닝
- 강화학습
- FirebaseV9
- Today
- Total
qcoding
[Ros Web] Roslib , Ros2djs를 활용한 web interface 만들기 #1 전체코드 본문
* ros 사용 시 로봇의 확장성을 위해 Brower를 통해서 로봇을 조작하는 interface를 만들기 위한 라이브러리 활용법을 정리하였다.
1) 전체구조
위의 전체 구조에서 보면 Ros와 Brower가 어떤 방식으로 소통하는 지 확인 할 수 있다. 우선 Brower는 roslibjs 패키지를 통해서 API를 활용하여 Web-Server와 소통가능하다. 이때 통신 방식으로는 Websocket 방식을 사용하고, JSON 형식의 포맷을 통해 메시지를 전달하게 된다. Web-Server는 간단히 python http server를 사용하였으며, Ros node와 소통을 하기 위한 rosbridge를 통해서 역시 JSON 형식으로 정보를 전달받는다. 이를 사용하기 위해 rosbridge 를 설치하여야 한다.
// ubuntu 18.04 및 Ros melodic 버전 사용 시
sudo apt-get install ros-melodic-rosbridge-server
2) 완성된 화면 및 기능
-> 위의 화면에서 Arrow는 로봇의 위치와 방향을 가르키며, map server에서 받아온 지도위에 로봇의 위치가 표시 된다. 아래의 initalPose와 GoalPose 클릭 시 각각의 위치를 설정할 수 있으며, 로봇에게 위치 정보를 전달하게 된다.
-> 로봇의 실제 동작을 위해 사용한 ros 프로그램은 turtlebot에 사용되는 AMCL , MOVE_BASE 패키지를 사용하여 작성하였다.
3) Client 코드
index.html
-> CDN 형태로 필요한 라이브러리를 Import 하며, ros2djs / roslibNav / roslib 라이브러리를 사용하였다.
<!DOCTYPE html>
<html>
<head>
<meta charset="utf-8" />
<!-- css -->
<script src="https://code.jquery.com/jquery-2.1.3.min.js"></script>
<!-- Latest compiled and minified CSS -->
<link rel="stylesheet" href="https://maxcdn.bootstrapcdn.com/bootstrap/3.3.4/css/bootstrap.min.css">
<!-- Optional theme -->
<link rel="stylesheet" href="https://maxcdn.bootstrapcdn.com/bootstrap/3.3.4/css/bootstrap-theme.min.css">
<!-- Latest compiled and minified JavaScript -->
<script src="https://maxcdn.bootstrapcdn.com/bootstrap/3.3.4/js/bootstrap.min.js"></script>
<!-- ros2djs -->
<script type="text/javascript" src="http://static.robotwebtools.org/EaselJS/current/easeljs.min.js"></script>
<script type="text/javascript" src="http://static.robotwebtools.org/EventEmitter2/current/eventemitter2.min.js"></script>
<script type="text/javascript" src="http://static.robotwebtools.org/ros2djs/current/ros2d.min.js"></script>
<!-- roslib -->
<script type="text/javascript" src="http://static.robotwebtools.org/roslibjs/current/roslib.min.js"></script>
<script type="text/javascript" src="https://cdnjs.cloudflare.com/ajax/libs/nipplejs/0.7.3/nipplejs.js"></script>
<!-- roslibNav -->
<script type="text/javascript" src="http://static.robotwebtools.org/nav2djs/current/nav2d.js"></script>
<!-- css -->
<link rel="stylesheet" href="css/css.css">
</head>
<body>
<h1>Simple ROS User Interface</h1>
<p>Connection status: <span id="status"></span></p>
<p>Last /txt_msg received: <span id="msg"></span></p>
<div class="container-fluid">
<div class="row-fluid">
<div class="span12">
<div class="row-fluid">
<button class="btn btn-default btn-xlarge" role="submit" onclick="move('LocationOne')">LocationOne</a>
<button class="btn btn-default btn-xlarge" role="submit" onclick="move('LocationTwo')">LocationTwo</a>
<button class="btn btn-default btn-xlarge" role="submit" onclick="move('LocationThree')">LocationThree</a>
<button class="btn btn-default btn-xlarge" role="submit" onclick="move('LocationFour')">LocationFour</a>
</div>
</div>
</div>
</div>
<div id="zone_joystick" style="width:200px; height: 200px;display: flex;justify-content: center;align-items: center;"></div>
<div id="map"></div>
<div id="nav"></div>
<div id="alerts">
</div>
<div class="joystick-container">
<div id="joystick"></div>
</div>
<div class="wrapper">
<div class="poseWrapper">
<h1>Initial Pose</h1>
<input type="checkbox" id="initialPoseswitch">
<label for="initialPoseswitch" class="switch_label">
<span class="onf_btn"></span>
</label>
</div>
<div class="poseWrapper">
<h1>Goal Pose</h1>
<input type="checkbox" id="goalPoseswitch">
<label for="goalPoseswitch" class="switch_label">
<span class="onf_btn"></span>
</label>
</div>
</div>
<p style="color:green">X:<span id="x"></span></p>
<p style="color:blue">Y:<span id="y"></span></p>
<script type="text/javascript" src="./script/roslisb.js"></script>
<script type="text/javascript" src="./script/joystick.js"></script>
</body>
</html>
css.css
.btn-xlarge {
padding: 20px 20px;
font-size: 20px;
line-height: normal;
-webkit-border-radius: 18px;
-moz-border-radius: 18px;
border-radius: 18px;
}
.wrapper {
width: 80%;
height: 150px;
text-align: center;
display: flex;
justify-content: space-evenly;
align-items: center;
}
#initialPoseswitch {
position: absolute;
/* hidden */
appearance: none;
-webkit-appearance: none;
-moz-appearance: none;
}
.switch_label {
position: relative;
cursor: pointer;
display: inline-block;
width: 58px;
height: 28px;
background: #fff;
border: 2px solid #daa;
border-radius: 20px;
transition: 0.2s;
}
.switch_label:hover {
background: #efefef;
}
.onf_btn {
position: absolute;
top: 4px;
left: 3px;
display: inline-block;
width: 20px;
height: 20px;
border-radius: 20px;
background: #daa;
transition: 0.2s;
}
/* checking style */
#initialPoseswitch:checked+.switch_label {
background: #c44;
border: 2px solid #c44;
}
#initialPoseswitch:checked+.switch_label:hover {
background: #e55;
}
/* move */
#initialPoseswitch:checked+.switch_label .onf_btn {
left: 34px;
background: #fff;
box-shadow: 1px 2px 3px #00000020;
}
#goalPoseswitch {
position: absolute;
/* hidden */
appearance: none;
-webkit-appearance: none;
-moz-appearance: none;
}
.switch_label {
position: relative;
cursor: pointer;
display: inline-block;
width: 58px;
height: 28px;
background: #fff;
border: 2px solid #daa;
border-radius: 20px;
transition: 0.2s;
}
.switch_label:hover {
background: #efefef;
}
.onf_btn {
position: absolute;
top: 4px;
left: 3px;
display: inline-block;
width: 20px;
height: 20px;
border-radius: 20px;
background: #daa;
transition: 0.2s;
}
/* checking style */
#goalPoseswitch:checked+.switch_label {
background: blue;
border: 2px solid blue;
}
#goalPoseswitch:checked+.switch_label:hover {
background: blue;
}
/* move */
#goalPoseswitch:checked+.switch_label .onf_btn {
left: 34px;
background: #fff;
box-shadow: 1px 2px 3px #00000020;
}
roslisb.js
// Ros WEB SOCKET SERVER CONF
var ros = new ROSLIB.Ros({
url : 'ws://localhost:9090'
});
ros.on('connection', function() {
document.getElementById("status").innerHTML = "Connected";
});
ros.on('error', function(error) {
document.getElementById("status").innerHTML = "Error";
});
ros.on('close', function() {
document.getElementById("status").innerHTML = "Closed";
});
// pathShape
var listenerforPath = new ROSLIB.Topic ({
ros : ros,
name : '/move_base/NavfnROS/plan',
messageType : 'nav_msgs/Path'
});
// TraceShape
var moveBaseFB = new ROSLIB.Topic ({
ros : ros,
name : '/move_base/feedback',
messageType : 'move_base_msgs/MoveBaseActionFeedback'
});
function mapLoad() {
// conf
let OperRatingMode="nav"
const CreatePoseTopic=(OperRatingMode)=>{
console.log(`Create posetopic , mode :${OperRatingMode}`)
if(OperRatingMode == "slam"){
console.log("poseTopic slam")
// Make robot pose subscriber
const SlamPoseTopic = new ROSLIB.Topic({
ros : ros,
name : '/tf',
messageType:'tf2_msgs/TFMessage'
// messageType : 'turtlesim/Pose'
// messageType : 'geometry_msgs/Pose'
})
return SlamPoseTopic
}else if(OperRatingMode=="nav"){
console.log("poseTopic nav")
const NavPoseTopic = new ROSLIB.Topic({
ros: ros,
name: '/amcl_pose',
messageType: 'geometry_msgs/PoseWithCovarianceStamped'
});
return NavPoseTopic
}
}
// poseTopic Publisher
let PoseTopic=CreatePoseTopic(OperRatingMode)
// Connect to ROS.
// Create the main viewer.
var viewer = new ROS2D.Viewer({
divID : 'map',
width : 700,
height : 700,
});
// Setup the map client.
var gridClient = new ROS2D.OccupancyGridClient({
ros : ros,
rootObject : viewer.scene,
image: 'turtlebot.png',
continuous: true
});
// robot odometry
var robotMarker = new ROS2D.ArrowShape({
size : 0.7,
strokeSize : 0.01,
pulse: true,
fillColor: createjs.Graphics.getRGB(255,0,0, 0.9),
});
// pathShape
var pathShape = new ROS2D.PathShape({
strokeSize : 0.03,
strokeColor : createjs.Graphics.getRGB(0, 255, 0,1),
});
gridClient.rootObject.addChild(pathShape);
listenerforPath.subscribe((message)=> {
if(message){
pathShape.setPath(message);
}
// listenerforPath.unsubscribe();
});
//Draw actual trace
var traceShape = new ROS2D.TraceShape({
strokeSize : 0.1,
strokeColor : createjs.Graphics.getRGB(255, 0, 0,0.5),
maxPoses : 250
});
gridClient.rootObject.addChild(traceShape);
//update on new message
moveBaseFB.subscribe(function(message) {
traceShape.addPose(message.feedback.base_position.pose);
});
// create initial Pose Topic and msg
const creatInitialPose=(pose_x,pose_y,orientation)=>{
const initialPose = new ROSLIB.Topic({
ros: ros,
name: '/initialpose',
messageType: 'geometry_msgs/PoseWithCovarianceStamped'
});
var posestamped_msg = new ROSLIB.Message({
header: {
stamp: {
secs : 0,
nsecs : 100
},
frame_id : "map"
},
pose: {
pose:{
position: {
x : pose_x,
y : pose_y,
z : 0.0
},
orientation: orientation
}
,
covariance: [0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.25, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.06853892326654787]
},
});
initialPose.publish(posestamped_msg)
console.log("initialPose publish")
}
// create Goal Pose Topic and msg
const creatGoalPose=(pose_x,pose_y,orientation)=>{
const goalPose = new ROSLIB.Topic({
ros: ros,
name: '/move_base_simple/goal',
messageType: 'geometry_msgs/PoseStamped'
});
var posestamped_msg = new ROSLIB.Message({
header: {
stamp: {
secs : 0,
nsecs : 100
},
frame_id : "map"
},
pose: {
position: {
x : pose_x,
y : pose_y,
z : 0.0
},
orientation: orientation
}
});
goalPose.publish(posestamped_msg)
console.log("goalPose publish")
}
// to set MouseMoevEvent after mouseDown event ,
let mouseDown=false
let mouseDownPose={}
// why MouseState set to up
var mouseEventHandler = function(event, mouseState,operMode) {
console.log(`mouseState :${mouseState}`)
if (mouseState === 'down'){
mouseDown=true
console.log("mouse down")
// get position when mouse button is pressed down
mouseDownPosition = viewer.scene.globalToRos(event.stageX, event.stageY);
mouseDownPositionVec3 = new ROSLIB.Vector3(mouseDownPosition);
mouseDownPose = new ROSLIB.Pose({
position: new ROSLIB.Vector3(mouseDownPositionVec3)
});
console.log(mouseDownPose.position)
}
else if (mouseState === 'move' && mouseDown){
console.log("mouse move")
// // remove obsolete orientation marker
gridClient.rootObject.removeChild(robotMarker);
}
else if (mouseState === 'up'&& mouseDown){
mouseDown=false
mouseUpPosition = viewer.scene.globalToRos(event.stageX, event.stageY);
mouseUpPositionVec3 = new ROSLIB.Vector3(mouseUpPosition);
const mouseUpPose = new ROSLIB.Pose({
position: new ROSLIB.Vector3(mouseUpPositionVec3)
});
// upPose - DownPose
xDelta = mouseUpPose.position.x - mouseDownPose.position.x ;
yDelta = mouseUpPose.position.y - mouseDownPose.position.y;
thetaRadians = Math.atan2(xDelta,yDelta);
thetaDegrees = thetaRadians * (180.0 / Math.PI);
if (thetaRadians >= 0 && thetaRadians <= Math.PI) {
thetaRadians += (3 * Math.PI / 2);
} else {
thetaRadians -= (Math.PI/2);
}
var qz = Math.sin(-thetaRadians/2.0);
var qw = Math.cos(-thetaRadians/2.0);
// degree convert to quaternion
var orientation = new ROSLIB.Quaternion({x:0, y:0, z:qz, w:qw});
// console.log(`xDelta : ${xDelta}, yDelta : ${yDelta} , degree : ${thetaDegrees}`)
// set robotmaker
if(operMode=="initial"){
creatInitialPose(mouseDownPose.position.x,mouseDownPose.position.y,orientation)
}else if (operMode=="goal")
creatGoalPose(mouseDownPose.position.x,mouseDownPose.position.y,orientation)
}};
viewer.scene.addEventListener('stagemousedown', function(event) {
let initialPoseChecked = document.querySelector("#initialPoseswitch").checked
let goalPoseChecked = document.querySelector("#goalPoseswitch").checked
// set Btn control
let operMode=initialPoseChecked?"initial":"goal"
// button to set inital pose
if(initialPoseChecked){
document.querySelector("#goalPoseswitch").checked=false
mouseEventHandler(event,'down',operMode);
}
if(goalPoseChecked){
document.querySelector("#initialPoseswitch").checked=false
mouseEventHandler(event,'down',operMode);
}
});
viewer.scene.addEventListener('stagemousemove', function(event) {
let initialPoseChecked = document.querySelector("#initialPoseswitch").checked
let goalPoseChecked = document.querySelector("#goalPoseswitch").checked
let operMode=initialPoseChecked?"initial":"goal"
// button to set inital pose
if(initialPoseChecked){
document.querySelector("#goalPoseswitch").checked=false
mouseEventHandler(event,'move',operMode);
}
if(goalPoseChecked){
document.querySelector("#initialPoseswitch").checked=false
mouseEventHandler(event,'move',operMode);
}
});
viewer.scene.addEventListener('stagemouseup', function(event) {
let initialPoseChecked = document.querySelector("#initialPoseswitch").checked
let goalPoseChecked = document.querySelector("#goalPoseswitch").checked
let operMode=initialPoseChecked?"initial":"goal"
// button to set inital pose
if(initialPoseChecked){
document.querySelector("#goalPoseswitch").checked=false
mouseEventHandler(event,'up',operMode);
}
if(goalPoseChecked){
document.querySelector("#initialPoseswitch").checked=false
mouseEventHandler(event,'up',operMode);
}
});
const createFunc = function (handlerToCall, discriminator, robotMarker,OperRatingMode) {
return discriminator.subscribe(function(pose){
if (OperRatingMode=="slam"){
// slam
// CrtoGrapher slam case(tf2_msgs/TFMessage)
console.log("slam work")
let odomPose = pose.transforms[0].transform.translation
let baseLinkPose=pose.transforms[1].transform.translation
// When using Nav, gemometry_msgs/Pose .orientation. {x,y,z,w} (Quarternion)
// When using SLAM tf2_msgs/TFMessage .transform . rotation {x,y,z,w} (quarternion)
let quaZ=pose.transforms[1].transform.rotation.z
// pose using odom
robotMarker.x = baseLinkPose.x;
robotMarker.y = -baseLinkPose.y;
let degreeZ = 0;
if( quaZ >= 0 ) {
degreeZ = quaZ / 1 * 180
} else {
degreeZ = (-quaZ) / 1 * 180 + 180
};
// degree
robotMarker.rotation = degreeZ;
}else if(OperRatingMode=="nav"){
// navigation
console.log("nav work")
robotMarker.x = pose.pose.pose.position.x;
robotMarker.y = -pose.pose.pose.position.y;
let orientationQuerter=pose.pose.pose.orientation
var q0 = orientationQuerter.w;
var q1 = orientationQuerter.x;
var q2 = orientationQuerter.y;
var q3 = orientationQuerter.z;
degree=-Math.atan2(2 * (q0 * q3 + q1 * q2), 1 - 2 * (q2 * q2 + q3 * q3)) * 180.0 / Math.PI
robotMarker.rotation = degree;
}
// rootObject를 통해서 robotMaker에 Marker 넣어줌
gridClient.rootObject.addChild(robotMarker);
})
}
// navigation pose / tf
createFunc('subscribe',PoseTopic, robotMarker,OperRatingMode);
// Scale the canvas to fit to the map
gridClient.on('change', function(){
viewer.scaleToDimensions(gridClient.currentGrid.width, gridClient.currentGrid.height);
viewer.shift(gridClient.currentGrid.pose.position.x, gridClient.currentGrid.pose.position.y);
});
}
// window.onload는 최종에 있는거 한번만 실행됨
window.addEventListener('onload',
console.log("mapload"),
mapLoad()
)
3) Server 코드
--> 서버 코드는 python http 기본 server로 만들었으며, 추가 필요가 있다면 웹프레임워크 flask / django를 활용할 수 있다.
import http.server
import socketserver
PORT = 8080
handler = http.server.SimpleHTTPRequestHandler
print("python webserver load")
with socketserver.TCPServer(("", PORT), handler) as httpd:
print("Server started at localhost:" + str(PORT))
httpd.serve_forever()
'Ros' 카테고리의 다른 글
[Ros Web] rosapi를 활용한 Topic /Node List 받아오기 #3 (6) | 2022.05.13 |
---|---|
[Ros Web] Roslib , Ros2djs를 활용한 web interface 만들기 #2 코드설명 (0) | 2022.05.12 |
3)[turtlebot_코드정리] navigation (0) | 2022.02.24 |
2)[turtlebot 코드정리] slam 코드 정리 (0) | 2022.02.24 |
1) [Turtlebot3 코드정리]gazebo를 통한 시뮬레이션 환경 (0) | 2022.02.24 |