-
Notifications
You must be signed in to change notification settings - Fork 4
hindbrain_beta documentation
(geometry_msgs/Twist) The output of the arbiter.
(std_msgs/Bool) A software switch, so that the robot can be stopped from the command line.
-
false
Trigger a software stop from ROS (default). This will stop the robot. -
true
Release the ROS software stop. This will start the robot if unhindered.
IMPORTANT!!! Unless you publish a message with the true
value it will not start.
rostopic pub /hind/enable std_msgs/Bool "data: true"
(std_msgs/Int16) The value of the global variable port_speed_actual
, the Servo speed value being sent to the port motors.
(std_msgs/Int16) The value of the global variable starboard_speed_actual
, the Servo speed value being sent to the starboard motors.
(std_msgs/String) The FSM state, plus the blame of the soft stop.
-
OK
mode = OK_MODE -
ESTOP
mode = PHYS_ESTOP_MODE -
SSTOP.BOTH
mode = SOFT_STOP_MODE, caused by both IR and Software -
SSTOP.ROS
mode = SOFT_STOP_MODE, caused by Software -
SSTOP.IR
mode = SOFT_STOP_MODE, caused by IR
The state machine has three states:
Signifies that the robot is not in any stopped mode.
Signifies that the EStop has been pressed. Overrides SOFT_STOP_MODE
.
Signifies that the Arduino has identified a software stop trigger.
States are handled by the global variable mode
. There are three states, controlled by the following code (which runs within loop):
if(is_EStop_ok() == false){
mode = PHYS_ESTOP_MODE;
}
else if(is_IR_ok() == true && is_ROS_ok() == true){
mode = OK_MODE;
}
else if(is_IR_ok() == false || is_ROS_ok() == false){
mode = SOFT_STOP_MODE;
}
The soft stop can be triggered by multiple things (the IR and a ROS subscription).
-
port_speed_commanded
andstarboard_speed_commanded
The port motor and starboard motor speed (Servo value) requested by the arbiter. As the arbiter may request really sharp changes in speed, this is not the value that gets sent directly to the motors. -
port_speed_actual
andstarboard_speed_actual
The actual speed that gets sent to the motors. The values of these variables are assigned in updateRampingSpeed().
The Arduino .ino code relies heavily on four header files, which are included at the top of the main sketch:
-
#include "includes.h"
: All the dependent libraries for this code. -
#include "defines.h"
: All of the constants, except for the pin assignments -
#include "pins.h"
: The pin assignments as constants -
#include "global.h"
: All of the global variables (and two callback prototypes for the ROS subscribers)