Skip to content

itb-atr/teleco_ros

 
 

Repository files navigation

SLAM / Navigation Stack for TELECO

created by ©︎niscode

Teleco-Vやペトラ台車 を使って、gmappingを用いたSLAM や、dwa(障害物回避)と自己位置推定(amcl)を用いたナビゲーション などを実行するためのlaunchファイルが格納されます。

For Teleco or Petra (vehicle part), this repository contains launch files to execute SLAM using gmapping, navigation using dwa (obstacle avoidance) and self-position estimation (amcl), etc.


[1/2] Build ROS-noetic (ROS1) in Ubuntu20.04


[2/2] Necessary Packages for Ubuntu20.04 / ROS-noetic (ROS1)

  • cd catkin_ws/src
  • git clone https://github.com/itb-atr/teleco_ros.git
  • git clone https://github.com/GT-RAIL/robot_pose_publisher.git
  • git clone https://github.com/rst-tu-dortmund/teb_local_planner.git
  • cd catkin_ws
  • catkin_make
  • source ~/.bashrc and .profile

Making a map by gmapping with following command.

  • roslaunch telecoV dual_gmapping.launch

Executing navigation with following command.

  • roslaunch telecoV dual_naivation.launch

Executing CAPF connection and launch all packages related to remote control.

  • rosrun telecoV bringup_telecoV.sh
    • you can modify the detail here.  ~/catkin_ws/src/teleco_ros/scripts/bringup_telecoV.sh

Additional Node Descriptions

waypoint_server_node.py

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

Subscribed Topics

clicked_point (geometry_msgs::PointStamped)

 Adds point with automatic name when using rviz’s “Publish Point” function.

Published Topics

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

Services

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.

Parameters

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.

patrol_node.py

This node offers functionality to control patrolling over a given waypoint list.

Uses: patrol.launch

Subscribed Topics

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.

Services

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.

Parameters

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.

safety_watchdog_simple.py

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.

Subscribed Topics

scan (sensor_msgs::LaserScan)

 Subscribes to laserScan topic and checks for proximity violations.

Published Topics

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.

Services

patrol/cancel (std_srvs::Empty)

 In case of obstacle is detected closer than the proximity threshold calls to end current patrol.

robot_status_node.py

This node collects information from several node and re-sends them in a custom message as a central information point.

Uses: robot_status.launch

Subscribed Topics

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.

Published Topics

robot_status/status (telecoV.msg::RobotStatus)

 Please check message definition for content information.

Parameters

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.

conveniences_server_node.py

This node offers basic functions for the base, which can be used to support the interaction.

Uses: convenience_server.launch

Subscribed Topics

robot_status/status (telecoV.msg::RobotStatus)

 For future use.

Published Topics

convenience_server/debug/goal_heading (geometry_msgs::PoseStamped)

 Publishes the requested heading for debug purposes.

Services

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.

Parameters

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.

About

No description, website, or topics provided.

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages

  • Python 58.6%
  • C++ 24.7%
  • Shell 10.1%
  • CMake 6.6%