Handles all command velocities and only allows the robot to move at all if no emergency stop is set and only move autonomous if autonomous operation is active.
More...
#include <RobotControlMux.h>
Handles all command velocities and only allows the robot to move at all if no emergency stop is set and only move autonomous if autonomous operation is active.
Definition at line 23 of file RobotControlMux.h.
◆ RobotControlMux()
| rsm::RobotControlMux::RobotControlMux |
( |
| ) |
|
◆ ~RobotControlMux()
| rsm::RobotControlMux::~RobotControlMux |
( |
| ) |
|
◆ autonomyCmdVelCallback()
| void rsm::RobotControlMux::autonomyCmdVelCallback |
( |
const geometry_msgs::Twist::ConstPtr & |
cmd_vel | ) |
|
|
private |
Callback for receiving the cmd vel produced by autonomous operation
- Parameters
-
| cmd_vel | Cmd vel from autonomous operation |
Definition at line 78 of file RobotControlMux.cpp.
◆ checkJoystickCommand()
| bool rsm::RobotControlMux::checkJoystickCommand |
( |
const sensor_msgs::Joy::ConstPtr & |
joy | ) |
|
|
private |
Checks if the given joystick command will make the robot move and is different to the previous one
- Parameters
-
- Returns
- If the new command will lead to a robot action
Definition at line 122 of file RobotControlMux.cpp.
◆ joystickCallback()
| void rsm::RobotControlMux::joystickCallback |
( |
const sensor_msgs::Joy::ConstPtr & |
joy | ) |
|
|
private |
Callback for receiving the commands issued from a connected joystick and checks if a new command was sent
- Parameters
-
Definition at line 102 of file RobotControlMux.cpp.
◆ publishCmdVel()
| void rsm::RobotControlMux::publishCmdVel |
( |
| ) |
|
|
private |
Publish the cmd vel controlling the robot depending on the current operation mode
Definition at line 50 of file RobotControlMux.cpp.
◆ publishOperationMode()
| void rsm::RobotControlMux::publishOperationMode |
( |
| ) |
|
|
private |
◆ publishTopics()
| void rsm::RobotControlMux::publishTopics |
( |
| ) |
|
Publishes msgs from all publishers in this class (cmd vel and operation mode)
Definition at line 45 of file RobotControlMux.cpp.
◆ setOperationMode()
| bool rsm::RobotControlMux::setOperationMode |
( |
rsm_msgs::SetOperationMode::Request & |
req, |
|
|
rsm_msgs::SetOperationMode::Response & |
res |
|
) |
| |
|
private |
◆ teleoperationCmdVelCallback()
| void rsm::RobotControlMux::teleoperationCmdVelCallback |
( |
const geometry_msgs::Twist::ConstPtr & |
cmd_vel | ) |
|
|
private |
Callback for receiving the cmd vel from teleoperation and checks if a command not equals zero was issued
- Parameters
-
| cmd_vel | Cmd vel from teleoperation |
Definition at line 83 of file RobotControlMux.cpp.
◆ teleoperationIdleTimerCallback()
| void rsm::RobotControlMux::teleoperationIdleTimerCallback |
( |
const ros::TimerEvent & |
event | ) |
|
|
private |
Timer callback for checking if teleoperation was stopped and robot is idle again
- Parameters
-
Definition at line 114 of file RobotControlMux.cpp.
◆ _autonomy_cmd_vel
| geometry_msgs::Twist rsm::RobotControlMux::_autonomy_cmd_vel |
|
private |
◆ _autonomy_cmd_vel_sub
◆ _autonomy_operation_cmd_vel_topic
| std::string rsm::RobotControlMux::_autonomy_operation_cmd_vel_topic |
|
private |
◆ _cmd_vel_pub
◆ _cmd_vel_topic
| std::string rsm::RobotControlMux::_cmd_vel_topic |
|
private |
◆ _emergency_stop_active
| bool rsm::RobotControlMux::_emergency_stop_active |
|
private |
◆ _joystick_cmd
| sensor_msgs::Joy rsm::RobotControlMux::_joystick_cmd |
|
private |
◆ _joystick_sub
◆ _joystick_topic
| std::string rsm::RobotControlMux::_joystick_topic |
|
private |
◆ _joystick_used
| bool rsm::RobotControlMux::_joystick_used |
|
private |
Is a joystick in use for controlling the robot
Definition at line 68 of file RobotControlMux.h.
◆ _nh
◆ _operation_mode
| int rsm::RobotControlMux::_operation_mode |
|
private |
Currently active mode of operation (0=stopped, 1=autonomous, 2=teleoperation)
Definition at line 60 of file RobotControlMux.h.
◆ _operation_mode_pub
◆ _set_operation_mode_service
◆ _teleoperation_cmd_vel
| geometry_msgs::Twist rsm::RobotControlMux::_teleoperation_cmd_vel |
|
private |
Last received command velocity from teleoperation
Definition at line 76 of file RobotControlMux.h.
◆ _teleoperation_cmd_vel_sub
◆ _teleoperation_cmd_vel_topic
| std::string rsm::RobotControlMux::_teleoperation_cmd_vel_topic |
|
private |
◆ _teleoperation_idle_timer
| ros::Timer rsm::RobotControlMux::_teleoperation_idle_timer |
|
private |
◆ _teleoperation_idle_timer_duration
| double rsm::RobotControlMux::_teleoperation_idle_timer_duration |
|
private |
Time until teleoperation mode will be stopped when no new message is received
Definition at line 56 of file RobotControlMux.h.
The documentation for this class was generated from the following files: