#include <xbot_ros.hpp>
Definition at line 86 of file xbot_ros.hpp.
Default constructor.
Make sure you call the init() method to fully define this node.
Definition at line 60 of file xbot_ros.cpp.
xbot::XbotRos::~XbotRos |
( |
| ) |
|
This will wait some time while xbot internally closes its threads and destructs itself.
Definition at line 78 of file xbot_ros.cpp.
Two groups of publishers, one required by turtlebot, the other for xbot esoterics.
Definition at line 295 of file xbot_ros.cpp.
void xbot::XbotRos::processBaseStreamData |
( |
| ) |
|
|
private |
void xbot::XbotRos::processSensorStreamData |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishBatteryState |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishCoreSensor |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishEchoData |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishExtraSensor |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishInertia |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishInfraredData |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishMotorState |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishPitchPlatformState |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishRawInertia |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishRobotState |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishSoundState |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishWheelState |
( |
| ) |
|
|
private |
void xbot::XbotRos::publishYawPlatformState |
( |
| ) |
|
|
private |
void xbot::XbotRos::subscribeLedCommand |
( |
const std_msgs::UInt8 |
msg | ) |
|
|
private |
void xbot::XbotRos::subscribeLiftCommand |
( |
const std_msgs::UInt8 |
msg | ) |
|
|
private |
void xbot::XbotRos::subscribeMotorEnableCommand |
( |
const std_msgs::Bool |
msg | ) |
|
|
private |
void xbot::XbotRos::subscribePitchPlatformCommand |
( |
const std_msgs::Int8 |
msg | ) |
|
|
private |
void xbot::XbotRos::subscribeResetOdometry |
( |
const std_msgs::EmptyConstPtr |
| ) |
|
|
private |
Play a predefined sound (single sound or sound sequence)
Reset the odometry variables.
Definition at line 76 of file subscriber_callbacks.cpp.
Two groups of subscribers, one required by turtlebot, the other for xbot esoterics.
Definition at line 337 of file xbot_ros.cpp.
void xbot::XbotRos::subscribeVelocityCommand |
( |
const geometry_msgs::TwistConstPtr |
msg | ) |
|
|
private |
void xbot::XbotRos::subscribeYawPlatformCommand |
( |
const std_msgs::Int8 |
msg | ) |
|
|
private |
bool xbot::XbotRos::update |
( |
| ) |
|
This is a worker function that runs in a background thread initiated by the nodelet. It gathers diagnostics information from the xbot driver, and broadcasts the results to the rest of the ros ecosystem.
Note that the actual driver data is collected via the slot callbacks in this class.
- Returns
- Bool : true/false if successfully updated or not (xbot driver shutdown).
Definition at line 245 of file xbot_ros.cpp.
ecl::Slot xbot::XbotRos::base_slot_stream_data |
|
private |
uint32_t xbot::XbotRos::base_timeout_times_ |
|
private |
bool xbot::XbotRos::cmd_vel_timed_out_ |
|
private |
bool xbot::XbotRos::first_sound_enabled_ |
|
private |
sensor_msgs::JointState xbot::XbotRos::joint_states |
|
private |
bool xbot::XbotRos::led_indicate_battery |
|
private |
int xbot::XbotRos::led_times_ |
|
private |
bool xbot::XbotRos::motor_enabled_ |
|
private |
ecl::Slot xbot::XbotRos::sensor_slot_stream_data |
|
private |
uint32_t xbot::XbotRos::sensor_timeout_times_ |
|
private |
bool xbot::XbotRos::sound_enabled_ |
|
private |
The documentation for this class was generated from the following files: