This namespace contains functions used in the uc_bridge node. More...
Functions | |
void | activateDAQ (Communication *com) |
This function will activate the daq of the serial device. More... | |
void | activateKinect (Communication *com) |
This function will activate the kinect power supply of the serial device. More... | |
void | activateMotorController (Communication *com) |
This function will activate the motor controller of the serial device. More... | |
void | activateSteeringController (Communication *com) |
This function will activate the steering controller of the serial device. More... | |
void | activateUS (Communication *com) |
This function will activate the ultra sonic range sensors of the serial device. More... | |
void | errorCallback (const std::string &msg) |
This function will be called whenever a communication error occured and post its content as a ROS Warning. More... | |
void | motorLevelCallback (std_msgs::Int16::ConstPtr motorLevel, Communication *com) |
This function will be called whenever a ros node published a message on the motor level topic. More... | |
void | publishDebugMessage (const std::string &msg, ros::Publisher *pub) |
This function will be called whenever the communication received any message if the debug mode is enabled. More... | |
void | publishSensorGroupMessage1 (SensorGroup *grp, std::unordered_map< std::string, ros::Publisher * > &pub) |
This function will be called whenever a message from sensor group 1 has been received and publish the sensor data on ros topcis. More... | |
void | publishSensorGroupMessage2 (SensorGroup *grp, std::unordered_map< std::string, ros::Publisher * > &pub) |
This function will be called whenever a message from sensor group 2 has been received and publish the sensor data on ros topcis. More... | |
void | publishSensorGroupMessage3 (SensorGroup *grp, std::unordered_map< std::string, ros::Publisher * > &pub) |
This function will be called whenever a message from sensor group 3 has been received and publish the sensor data on ros topcis. More... | |
void | publishSensorGroupMessage4 (SensorGroup *grp, std::unordered_map< std::string, ros::Publisher * > &pub) |
This function will be called whenever a message from sensor group 4 has been received and publish the sensor data on ros topcis. More... | |
void | publishSensorGroupMessage5 (SensorGroup *grp, std::unordered_map< std::string, ros::Publisher * > &pub) |
This function will be called whenever a message from sensor group 5 has been received and publish the sensor data on ros topcis. More... | |
void | publishSensorGroupMessage6 (SensorGroup *grp, std::unordered_map< std::string, ros::Publisher * > &pub) |
This function will be called whenever a message from sensor group 6 has been received and publish the sensor data on ros topcis. More... | |
void | registerSensorGroups (Communication *com) |
This function will trigger the registration of all predefined sensor groups on the serial device. More... | |
void | resetController (Communication *com) |
This function send a soft reset command to the serial device. More... | |
void | shutdownSignalHandler (int sig) |
This function is the callback for the shutdown system signal. More... | |
void | steeringLevelCallback (std_msgs::Int16::ConstPtr steeringLevel, Communication *com) |
This function will be called whenever a ros node published a message on the steering level topic. More... | |
void | textCallback (const std::string &msg) |
This function will be called whenever the communication received a plain text message which will be posted as ROS Info. More... | |
void | ucBoardMessageCallback (std_msgs::String::ConstPtr msg, Communication *com) |
This function will be called whenever a ros node published a message on the raw communication topic. More... | |
Variables | |
Communication * | com_ptr |
bool | rstOnShutdown |
This namespace contains functions used in the uc_bridge node.
Functions in this namespace are setup/calibration functions, sensor group callbacks and ros topic callbacks.
void uc_bridge::activateDAQ | ( | Communication * | com | ) |
This function will activate the daq of the serial device.
[in] | com | Pointer to a Communication object. |
Definition at line 207 of file uc_bridge.h.
void uc_bridge::activateKinect | ( | Communication * | com | ) |
This function will activate the kinect power supply of the serial device.
[in] | com | Pointer to a Communication object. |
Definition at line 160 of file uc_bridge.h.
void uc_bridge::activateMotorController | ( | Communication * | com | ) |
This function will activate the motor controller of the serial device.
[in] | com | Pointer to a Communication object. |
Definition at line 108 of file uc_bridge.h.
void uc_bridge::activateSteeringController | ( | Communication * | com | ) |
This function will activate the steering controller of the serial device.
[in] | com | Pointer to a Communication object. |
Definition at line 134 of file uc_bridge.h.
void uc_bridge::activateUS | ( | Communication * | com | ) |
This function will activate the ultra sonic range sensors of the serial device.
[in] | com | Pointer to a Communication object. |
Definition at line 184 of file uc_bridge.h.
void uc_bridge::errorCallback | ( | const std::string & | msg | ) |
This function will be called whenever a communication error occured and post its content as a ROS Warning.
[in] | msg | error message |
Definition at line 432 of file uc_bridge.h.
void uc_bridge::motorLevelCallback | ( | std_msgs::Int16::ConstPtr | motorLevel, |
Communication * | com | ||
) |
This function will be called whenever a ros node published a message on the motor level topic.
The content of the motor level message determines what motor level will be set. This is an alternative way to ros services for controlling the robot.
[in] | motorLevel | motor level message containing the motor level to be set. |
[in] | com | Pointer to a Communication object. |
Definition at line 470 of file uc_bridge.h.
void uc_bridge::publishDebugMessage | ( | const std::string & | msg, |
ros::Publisher * | pub | ||
) |
This function will be called whenever the communication received any message if the debug mode is enabled.
The content of the debug message will be published on a ros topic.
[in] | msg | plain debug message |
[out] | pub | ros::Publisher for the debug topic |
Definition at line 453 of file uc_bridge.h.
void uc_bridge::publishSensorGroupMessage1 | ( | SensorGroup * | grp, |
std::unordered_map< std::string, ros::Publisher * > & | pub | ||
) |
This function will be called whenever a message from sensor group 1 has been received and publish the sensor data on ros topcis.
Sensor group 1 contains all ultra sonic range sensor readings.
[in] | grp | Pointer to SensorGroup 1 object |
[in] | map | of ros::Publisher objects. |
Definition at line 236 of file uc_bridge.h.
void uc_bridge::publishSensorGroupMessage2 | ( | SensorGroup * | grp, |
std::unordered_map< std::string, ros::Publisher * > & | pub | ||
) |
This function will be called whenever a message from sensor group 2 has been received and publish the sensor data on ros topcis.
Sensor group 2 contains all IMU sensor readings.
[in] | grp | Pointer to SensorGroup 2 object |
[in] | map | of ros::Publisher objects. |
Definition at line 290 of file uc_bridge.h.
void uc_bridge::publishSensorGroupMessage3 | ( | SensorGroup * | grp, |
std::unordered_map< std::string, ros::Publisher * > & | pub | ||
) |
This function will be called whenever a message from sensor group 3 has been received and publish the sensor data on ros topcis.
Sensor group 3 contains all hall sensor readings (makshift rotary encoder).
[in] | grp | Pointer to SensorGroup 3 object |
[in] | map | of ros::Publisher objects. |
Definition at line 322 of file uc_bridge.h.
void uc_bridge::publishSensorGroupMessage4 | ( | SensorGroup * | grp, |
std::unordered_map< std::string, ros::Publisher * > & | pub | ||
) |
This function will be called whenever a message from sensor group 4 has been received and publish the sensor data on ros topcis.
Sensor group 4 contains all magnetic field sensor readings.
[in] | grp | Pointer to SensorGroup 4 object |
[in] | map | of ros::Publisher objects. |
Definition at line 348 of file uc_bridge.h.
void uc_bridge::publishSensorGroupMessage5 | ( | SensorGroup * | grp, |
std::unordered_map< std::string, ros::Publisher * > & | pub | ||
) |
This function will be called whenever a message from sensor group 5 has been received and publish the sensor data on ros topcis.
Sensor group 5 contains all battery readings.
[in] | grp | Pointer to SensorGroup 5 object |
[in] | map | of ros::Publisher objects. |
Definition at line 377 of file uc_bridge.h.
void uc_bridge::publishSensorGroupMessage6 | ( | SensorGroup * | grp, |
std::unordered_map< std::string, ros::Publisher * > & | pub | ||
) |
This function will be called whenever a message from sensor group 6 has been received and publish the sensor data on ros topcis.
Sensor group 6 contains hall sensor readings for time between 8 impulses.
[in] | grp | Pointer to SensorGroup 6 object |
[in] | map | of ros::Publisher objects. |
Definition at line 409 of file uc_bridge.h.
void uc_bridge::registerSensorGroups | ( | Communication * | com | ) |
This function will trigger the registration of all predefined sensor groups on the serial device.
[in] | com | Pointer to a Communication object. |
Definition at line 89 of file uc_bridge.h.
void uc_bridge::resetController | ( | Communication * | com | ) |
This function send a soft reset command to the serial device.
[in] | com | Pointer to a Communication object. |
Definition at line 42 of file uc_bridge.h.
void uc_bridge::shutdownSignalHandler | ( | int | sig | ) |
This function is the callback for the shutdown system signal.
If the OS catches a shutdown system signal (e.g. ctrl+x in command line) this function will be called and shut down the serial connection.
[in] | sig | shutdown signal |
Definition at line 64 of file uc_bridge.h.
void uc_bridge::steeringLevelCallback | ( | std_msgs::Int16::ConstPtr | steeringLevel, |
Communication * | com | ||
) |
This function will be called whenever a ros node published a message on the steering level topic.
The content of the steering level message determines what motor level will be set. This is an alternative way to ros services for controlling the robot.
[in] | steeringLevel | steering level message containing the steering level to be set. |
[in] | com | Pointer to a Communication object. |
Definition at line 507 of file uc_bridge.h.
void uc_bridge::textCallback | ( | const std::string & | msg | ) |
This function will be called whenever the communication received a plain text message which will be posted as ROS Info.
[in] | msg | plain text message |
Definition at line 441 of file uc_bridge.h.
void uc_bridge::ucBoardMessageCallback | ( | std_msgs::String::ConstPtr | msg, |
Communication * | com | ||
) |
This function will be called whenever a ros node published a message on the raw communication topic.
The content of the message will be transmitted directly to the serial device. This is meant as a direct way to communicate with the serial device for debugging purposes.
[in] | msg | message to be transmitted |
[in] | com | Pointer to a Communication object. |
Definition at line 541 of file uc_bridge.h.
Communication* uc_bridge::com_ptr |
Pointer to a Communication object.
Definition at line 35 of file uc_bridge.h.
bool uc_bridge::rstOnShutdown |
Should the serial device be reset before shutdown?
Definition at line 36 of file uc_bridge.h.