created by ©︎niscode
ここではTeleco-V(台車)を使って、
- gmappingを用いたSLAM や、
- dwa(障害物回避)と自己位置推定(amcl)を用いたナビゲーション などを実行するためのlaunchファイルが格納されます。
git clone git@github.com:niscode/scripts.git
- 上記のリポジトリをホームディレクトリに配置後、$ ./ros-noetic-setup.sh を実行。
- 手順通りに進めると $ roscore できるようになります。
sudo apt -y install ros-noetic-rosserial
sudo apt -y install ros-noetic-slam-gmapping
sudo apt -y install ros-noetic-navigation
ros-noetic-map-server
ros-noetic-jsk-visualization
cd catkin_ws/src
git clone https://github.com/niscode/telecoV.git
git clone https://github.com/Slamtec/rplidar_ros.git
git clone https://github.com/iralabdisco/ira_laser_tools.git
git clone https://github.com/GT-RAIL/robot_pose_publisher.git
cd catkin_ws
catkin_make
roscd telecoV/scripts
nano rplidar.rules
- 上記ファイルを編集して、対応するRPLiDARや台車のボードのシリアルNoを指定します。
./create_udev_rules.sh
sudo reboot
roslaunch telecoV dual_gmapping.launch
roslaunch telecoV dual_naivation.launch
rosrun telecoV cylinder.py
- スライダーを上下に動かし、任意の位置で Update ボタンを押すことで動作します。
- ※
rosrun rosserial_python serial_node.py _port:=/dev/ROVER_BOARD _baud:=115200
が実行中か、 navigationなどのパッケージ実行中のみ、昇降が可能です。
This node offers local waypoint setting, serializing, de-serializing and editing functions (CRUD). It publishes the most recent set of waypoints on the topic “/waypoint_server/waypoints” and uses InteractiveMarkers to allow easy editing of the waypoints with rviz. It offers its full functionality via an optional local CLI (check help command) and exposes basic functions through service calls.
Uses: waypoint_server.launch
clicked_point (geometry_msgs::PointStamped)
Adds point with automatic name when using rviz’s “Publish Point” function.
waypoint_server/waypoints (telecoV.msg::WaypointArray)
Publishes most recent local waypoints
move_base/goal (move_base_msgs::MoveBaseActionGoal)
Used for “Navigate Here” function of InteractiveMarkers
move_base/cancel (actionlib_msgs::GoalID)
Used for the “stop” navigation function of the CLI
waypoint_server/add (telecoV.srv::WaypointService)
Adds a new waypoint at 0,0,0 with name of argument string.
waypoint_server/remove (telecoV.srv::WaypointService)
Removes waypoint with name of argument string.
waypoint_server/add_here (telecoV.srv::WaypointService)
Adds a new waypoint robot position with name of argument string.
waypoint_server/waypoint_filepath (string, default: "/tmp/waypoints.bin")
Filepath of were to safe the waypoints after node gets closed.
waypoint_server/reference_frame (string, default: "map")
Reference frame for the waypoints.
waypoint_server/robot_frame (string, default: "base_link")
Robot frame the transform from the reference frame is used of.
waypoint_server/cli (bool, default: "False")
Whether to spawn a command line in the console. If it is used it should be ended via the "quit" command before Ctrl-C kills the node.
This node offers functionality to control patrolling over a given waypoint list.
Uses: patrol.launch
waypoint_server/waypoints (telecoV.msg::WaypointArray)
Used to always patrol to the most up-to-date waypoints.
move_base/status (actionlib_msgs::GoalStatusArray)
Internally used to determine behavior based on navigation state.
patrol/start (telecoV.srv::PatrolService)
If empty -> random patrol, if one waypoint -> drive to point and end patrol, if len(waypoints) > 1 -> drive to waypoints in given order and start over at end.
patrol/cancel (std_srvs::Empty)
Ends patrol after reaching current waypoint.
waypoint_server/reference_frame (string, default: "map")
Reference frame for the waypoints.
waypoint_server/robot_frame (string, default: "base_link")
Robot frame the transform from the reference frame is used of.
This node constantly monitors the LaserScan data published on “/scan” and if proximity falls short of threshold cancels the patrol and the current navigation so that the robot stops. The teleoperator has to make sure the robot gets moved out of the obstacle and then can restart the patrol.
scan (sensor_msgs::LaserScan)
Subscribes to laserScan topic and checks for proximity violations.
move_base/cancel (actionlib_msgs::GoalID)
In case of obstacle is detected closer than the proximity threshold cancel current navigation and stop robot at its current location.
patrol/cancel (std_srvs::Empty)
In case of obstacle is detected closer than the proximity threshold calls to end current patrol.
This node collects information from several node and re-sends them in a custom message as a central information point.
Uses: robot_status.launch
move_base/status (move_base_msgs::GoalStatusArray)
Listens to get the latest status of the navigation stack.
move_base/goal (move_base_msgs::MoveBaseActionGoal)
Listens to know the latest navigation goal.
robot_status/console_msg (telecoV.msg::StringArray)
Listens to custom string array message which can be appended to a log window on the operator side.
robot_status/status (telecoV.msg::RobotStatus)
Please check message definition for content information.
waypoint_server/reference_frame (string, default: "map")
Reference frame for the waypoints.
waypoint_server/robot_frame (string, default: "base_link")
Robot frame the transform from the reference frame is used of.
This node offers basic functions for the base, which can be used to support the interaction.
Uses: convenience_server.launch
robot_status/status (telecoV.msg::RobotStatus)
For future use.
convenience_server/debug/goal_heading (geometry_msgs::PoseStamped)
Publishes the requested heading for debug purposes.
convenience_server/goal_heading (telecoV.srv::GoalHeadingService)
Requests the relative rotation of the robot in reference to the given goal.
convenience_server/relative_turn (telecoV.srv::RelativeTurnService)
Uses move_base to turn the robot in-place by the given rotation value.
waypoint_server/reference_frame (string, default: "map")
Reference frame for the waypoints.
waypoint_server/robot_frame (string, default: "base_link")
Robot frame the transform from the reference frame is used of.