## repository: https://github.com/danielsnider/lost_comms_recovery <> <> == Overview == If your robot loses connection to the base station it will navigate to a configurable home. The base station connection check uses ping to a configurable list of IPs. == Quick Start == 1. Install: {{{ $ sudo apt-get install ros-kinetic-lost-comms-recovery }}} 2. Launch: {{{ $ roslaunch lost_comms_recovery lost_comms_recovery.launch ips_to_monitor:=192.168.1.2 }}} == Details == This node is not real-time safe. The monitoring loop waits 3 seconds between checks. === If move_base is running === If move_base is running, an autonomous recovery navigation will take place. The default position of the recovery goal is the origin (0,0) of the frame given it the goal_frame_id param and the orientation is all 0s by default. This default pose can be overridden if a messaged is published on the recovery_pose topic. If move_base is already navigating to a goal it will not be interrupted and recovery navigation will happen when move_base is idle. === If move_base is not running === If move_base is not running when communication failure occurs then motors and joysticks are set to zero by publishing a zero `geometry_msgs/Twist` message and a zero `sensor_msgs/Joy` message. '''Important''': Instead of relying on this this feature, you're better off with motor control software that sets zero velocity after a certain amount of time not receiving any new commands. == Nodes == {{{ #!clearsilver CS/NodeAPI name = lost_comms_recovery pub { 0.name = cmd_vel 0.type = geometry_msgs/Twist 0.desc = Send a zero `Twist` message on this topic when communication to the base station is lost. 1.name = joy 1.type = sensor_msgs/Joy 1.desc = Send a zero `Joy` message on this topic when communication to the base station is lost. } sub { 0.name = recovery_pose 0.type = geometry_msgs/PoseWithCovarianceStamped 0.desc = A pose that the robot will recover to if communication to the base station is lost. This will override the default recovery goal which is to the origin (0,0) of the `goal_frame_id` param. } param { 0.name = ~goal_frame_id 0.type = string 0.desc = The [[tf]] frame for `move_base` goals. 0.default = map 1.name = ~ping_fail_count 1.type = int 1.desc = Number of pings that must fail for communication to be considered lost. Each ping waits 1 second for a response. 1.default = 2 2.name = ~ips_to_monitor 2.type = string 2.desc = Comma separated list of IPs to monitor using ping. 2.default = 192.168.1.2,192.168.1.3 } act_called { 0.name = move_base 0.type = move_base_msgs/MoveBaseAction 0.desc = The move_base action server performs the autonomous recovery navigation. } }}} == Use Case == === Use in the University Rover Competition (URC) === This functionality is helpful for the autonomous task of the University Rover Competition (URC) and we hope this helps you. == Normal Output == {{{ $ roslaunch lost_comms_recovery lost_comms_recovery.launch ips_to_monitor:=192.168.190.136 [INFO] Monitoring base station on IP(s): 192.168.190.136. [INFO] Connected to base station. [INFO] Connected to base station. ... [ERROR] No connection to base station. [INFO] Executing move_base goal to position (x,y) 0.0, 0.0. [INFO] Initial goal status: PENDING [INFO] This goal has been accepted by the simple action server [INFO] Final goal status: SUCCEEDED [INFO] Goal reached. }}}