Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

turtlebot bringup #1

Open
wants to merge 11 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions rchomeedu_mapping/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,13 @@

### Specific instructions for Turtlebot

**Command-line interface**

cd $CATKIN_WS/src/robot_bringup
roslaunch ./start_turtle.launch

cd $CATKIN_WS/src/robocup_nav_tutorial
roslaunch ./map_setup.launch


### Specific instructions for MARRtino
Expand Down
19 changes: 17 additions & 2 deletions rchomeedu_navigation/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,23 @@
* path planner (e.g., move_base)

### Specific instructions for Turtlebot


**Command-line interface**
```
cd ~/catkin/src/robocup_nav_tutorial/launch
```
modify the launch file named navigation.launch, change the path with your map path

```
<arg name="map_file" default="/home/usrname/catkin_ws/src/robocup_nav_tutorial/launch/maps/your_map_name.yaml" />
```
start your robot
```
roslaunch robot_bringup start_turtle.launch
```
start navigation
```
roslaunch robocup_nav_tutorial navigation_turtle.launch
```

### Specific instructions for MARRtino

Expand Down
41 changes: 41 additions & 0 deletions rchomeedu_navigation/launch/navigation_turtle.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
<!--这是获取位置的launch文件-->
<launch>
<!-- 唤醒turtlebot -->
<!--include file="$(find turtlebot_bringup)/launch/minimal.launch" /-->

<!-- 设置摄像头参数 -->
<!--include file="$(find turtlebot_bringup)/launch/3dsensor.launch">
<arg name="rgb_processing" value="false" />
<arg name="depth_registration" value="false" />
<arg name="depth_processing" value="false" />
<arg name="scan_topic" value="/scan" />
<arg name="camera" value="camera" />
</include-->

<!-- 加载地图 -->
<arg name="map_file" default="/home/hts/ROS_test/src/nav_test/launch/maps/314.yaml" />
<node pkg="map_server" type="map_server" name="map_server" args="$(arg map_file)" />

<!-- 设置amcl-->
<arg name="initial_pose_x" default="0.0"/> <!-- 设置初始坐标 -->
<arg name="initial_pose_y" default="0.0"/>
<arg name="initial_pose_a" default="0.0"/>

<include file="$(find turtlebot_navigation)/launch/includes/amcl/amcl.launch.xml">
<arg name="initial_pose_x" value="$(arg initial_pose_x)"/>
<arg name="initial_pose_y" value="$(arg initial_pose_y)"/>
<arg name="initial_pose_a" value="$(arg initial_pose_a)"/>
</include>

<!-- 加载move_base -->
<include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml"/>

<!-- 3D visualization -->
<include file="$(find turtlebot_rviz_launchers)/launch/view_navigation.launch" />
<!--
手柄操作设置如下
-->
<!-- 速度平滑 -->
<include file="$(find turtlebot_teleop)/launch/keyboard_teleop.launch" />

</launch>
82 changes: 82 additions & 0 deletions rchomeedu_navigation/scripts/save_waypoint.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
#!/urs/bin/env python
# -*- encoding:UTF-8 -*-

import rospy
from geometry_msgs.msg import PoseWithCovarianceStamped
from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal

class get_point():

def __init__(self):

rospy.init_node("save_point")
self.point_dataset = []
self.point_num = []
self.switch=True
con = True
print 'use keyboard to control your robot'
print 'please input point_id if you want to exit please input stop'
while con:
print 'Get the waypoint : '
str = raw_input()
if self.switch == True:
if str != 'stop':
self.switch = False
self.point_num.append(str)
self.save_waypoint()
else:
con=False
self.write2txt()
rospy.sleep(2)


def save_waypoint(self):

rospy.loginfo("save_point")
amcl_sub = rospy.Subscriber('/amcl_pose', PoseWithCovarianceStamped, self.amcl_callback)

def amcl_callback(self, msg):

my_point = MoveBaseGoal()
my_point.target_pose.header.frame_id = '/map'
my_point.target_pose.header.seq = msg.header.seq
my_point.target_pose.header.stamp = msg.header.stamp
my_point.target_pose.pose.position.x = msg.pose.pose.position.x
my_point.target_pose.pose.position.y = msg.pose.pose.position.y
my_point.target_pose.pose.position.z = msg.pose.pose.position.z
my_point.target_pose.pose.orientation.x = msg.pose.pose.orientation.x
my_point.target_pose.pose.orientation.y = msg.pose.pose.orientation.y
my_point.target_pose.pose.orientation.z = msg.pose.pose.orientation.z
my_point.target_pose.pose.orientation.w = msg.pose.pose.orientation.w
self.point_dataset.append(my_point)
rospy.loginfo("Point saved successfully!")
self.switch = True

def write2txt(self):

f = open('/home/hts/ROS_test/src/nav_test/src/waypoints.txt','w')
for point in range (len(self.point_dataset)):
f.write(self.point_num[point])
f.write(' ')
f.write('position ')
f.write('x '+str(self.point_dataset[point].target_pose.pose.position.x)+' ')
f.write('y '+str(self.point_dataset[point].target_pose.pose.position.y)+' ')
f.write('z '+str(self.point_dataset[point].target_pose.pose.position.z)+' ')
f.write('orientation ')
f.write('x '+str(self.point_dataset[point].target_pose.pose.orientation.x)+' ')
f.write('y '+str(self.point_dataset[point].target_pose.pose.orientation.y)+' ')
f.write('z '+str(self.point_dataset[point].target_pose.pose.orientation.z)+' ')
f.write('w '+str(self.point_dataset[point].target_pose.pose.orientation.w)+' ')
f.write('\n')


if __name__ == "__main__":

try :
get_point()
except rospy.ROSInterruptException:
print "------save_point_error!------"