Public Member Functions | Private Member Functions | Private Attributes | List of all members
xbot::XbotRos Class Reference

#include <xbot_ros.hpp>

Public Member Functions

bool init (ros::NodeHandle &nh)
 
bool update ()
 
 XbotRos (std::string &node_name)
 Default constructor. More...
 
 ~XbotRos ()
 

Private Member Functions

void advertiseTopics (ros::NodeHandle &nh)
 
void processBaseStreamData ()
 
void processSensorStreamData ()
 
void publishBatteryState ()
 
void publishCoreSensor ()
 
void publishEchoData ()
 
void publishExtraSensor ()
 
void publishInertia ()
 
void publishInfraredData ()
 
void publishMotorState ()
 
void publishPitchPlatformState ()
 
void publishRawInertia ()
 
void publishRobotState ()
 
void publishSoundState ()
 
void publishWheelState ()
 
void publishYawPlatformState ()
 
void subscribeLedCommand (const std_msgs::UInt8)
 
void subscribeLiftCommand (const std_msgs::UInt8)
 
void subscribeMotorEnableCommand (const std_msgs::Bool)
 
void subscribePitchPlatformCommand (const std_msgs::Int8)
 
void subscribeResetOdometry (const std_msgs::EmptyConstPtr)
 Play a predefined sound (single sound or sound sequence) More...
 
void subscribeSoundCommand (const std_msgs::Bool)
 
void subscribeTopics (ros::NodeHandle &nh)
 
void subscribeVelocityCommand (const geometry_msgs::TwistConstPtr)
 
void subscribeYawPlatformCommand (const std_msgs::Int8)
 

Private Attributes

ecl::Slot base_slot_stream_data
 
uint32_t base_timeout_times_
 
ros::Publisher battery_state_publisher
 
bool cmd_vel_timed_out_
 
ros::Publisher core_sensor_publisher
 
ros::Publisher extra_sensor_publisher
 
bool first_sound_enabled_
 
ros::Publisher front_echo_data_publisher
 
ros::Publisher imu_data_publisher
 
ros::Publisher infrared_data_publisher
 
ros::Publisher joint_state_publisher
 
sensor_msgs::JointState joint_states
 
ros::Subscriber led_command_subscriber
 
bool led_indicate_battery
 
int led_times_
 
ros::Subscriber motor_enable_command_subscriber
 
bool motor_enabled_
 
ros::Publisher motor_state_publisher
 
std::string name
 
Odometry odometry
 
ros::Subscriber pitch_platform_command_subscriber
 
ros::Publisher pitch_platform_state_publisher
 
int8_t ppd_
 
ros::Publisher raw_imu_data_publisher
 
ros::Publisher rear_echo_data_publisher
 
ros::Subscriber reset_odometry_subscriber
 
ros::Publisher robot_state_publisher
 
ecl::Slot sensor_slot_stream_data
 
uint32_t sensor_timeout_times_
 
ros::Subscriber sound_command_subscriber
 
bool sound_enabled_
 
ros::Publisher sound_state_publisher
 
ros::Subscriber velocity_command_subscriber
 
Xbot xbot
 
ros::Subscriber yaw_platform_command_subscriber
 
ros::Publisher yaw_platform_state_publisher
 
int8_t ypd_
 

Detailed Description

Definition at line 86 of file xbot_ros.hpp.

Constructor & Destructor Documentation

xbot::XbotRos::XbotRos ( std::string node_name)

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.

Member Function Documentation

void xbot::XbotRos::advertiseTopics ( ros::NodeHandle nh)
private

Two groups of publishers, one required by turtlebot, the other for xbot esoterics.

Definition at line 295 of file xbot_ros.cpp.

bool xbot::XbotRos::init ( ros::NodeHandle nh)

Definition at line 87 of file xbot_ros.cpp.

void xbot::XbotRos::processBaseStreamData ( )
private

Definition at line 49 of file slot_callbacks.cpp.

void xbot::XbotRos::processSensorStreamData ( )
private

Definition at line 212 of file slot_callbacks.cpp.

void xbot::XbotRos::publishBatteryState ( )
private

Definition at line 170 of file slot_callbacks.cpp.

void xbot::XbotRos::publishCoreSensor ( )
private

Definition at line 85 of file slot_callbacks.cpp.

void xbot::XbotRos::publishEchoData ( )
private

Definition at line 113 of file slot_callbacks.cpp.

void xbot::XbotRos::publishExtraSensor ( )
private

Definition at line 220 of file slot_callbacks.cpp.

void xbot::XbotRos::publishInertia ( )
private

Definition at line 261 of file slot_callbacks.cpp.

void xbot::XbotRos::publishInfraredData ( )
private

Definition at line 139 of file slot_callbacks.cpp.

void xbot::XbotRos::publishMotorState ( )
private

Definition at line 159 of file slot_callbacks.cpp.

void xbot::XbotRos::publishPitchPlatformState ( )
private

Definition at line 327 of file slot_callbacks.cpp.

void xbot::XbotRos::publishRawInertia ( )
private

Definition at line 293 of file slot_callbacks.cpp.

void xbot::XbotRos::publishRobotState ( )
private

Definition at line 192 of file slot_callbacks.cpp.

void xbot::XbotRos::publishSoundState ( )
private

Definition at line 339 of file slot_callbacks.cpp.

void xbot::XbotRos::publishWheelState ( )
private

Definition at line 62 of file slot_callbacks.cpp.

void xbot::XbotRos::publishYawPlatformState ( )
private

Definition at line 315 of file slot_callbacks.cpp.

void xbot::XbotRos::subscribeLedCommand ( const std_msgs::UInt8  msg)
private

Definition at line 110 of file subscriber_callbacks.cpp.

void xbot::XbotRos::subscribeLiftCommand ( const std_msgs::UInt8  msg)
private

Definition at line 96 of file subscriber_callbacks.cpp.

void xbot::XbotRos::subscribeMotorEnableCommand ( const std_msgs::Bool  msg)
private

Definition at line 91 of file subscriber_callbacks.cpp.

void xbot::XbotRos::subscribePitchPlatformCommand ( const std_msgs::Int8  msg)
private

Definition at line 106 of file subscriber_callbacks.cpp.

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.

void xbot::XbotRos::subscribeSoundCommand ( const std_msgs::Bool  msg)
private

Definition at line 115 of file subscriber_callbacks.cpp.

void xbot::XbotRos::subscribeTopics ( ros::NodeHandle nh)
private

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

Definition at line 53 of file subscriber_callbacks.cpp.

void xbot::XbotRos::subscribeYawPlatformCommand ( const std_msgs::Int8  msg)
private

Definition at line 101 of file subscriber_callbacks.cpp.

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.

Member Data Documentation

ecl::Slot xbot::XbotRos::base_slot_stream_data
private

Definition at line 160 of file xbot_ros.hpp.

uint32_t xbot::XbotRos::base_timeout_times_
private

Definition at line 104 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::battery_state_publisher
private

Definition at line 119 of file xbot_ros.hpp.

bool xbot::XbotRos::cmd_vel_timed_out_
private

Definition at line 102 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::core_sensor_publisher
private

Definition at line 115 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::extra_sensor_publisher
private

Definition at line 116 of file xbot_ros.hpp.

bool xbot::XbotRos::first_sound_enabled_
private

Definition at line 109 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::front_echo_data_publisher
private

Definition at line 125 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::imu_data_publisher
private

Definition at line 122 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::infrared_data_publisher
private

Definition at line 124 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::joint_state_publisher
private

Definition at line 126 of file xbot_ros.hpp.

sensor_msgs::JointState xbot::XbotRos::joint_states
private

Definition at line 100 of file xbot_ros.hpp.

ros::Subscriber xbot::XbotRos::led_command_subscriber
private

Definition at line 139 of file xbot_ros.hpp.

bool xbot::XbotRos::led_indicate_battery
private

Definition at line 108 of file xbot_ros.hpp.

int xbot::XbotRos::led_times_
private

Definition at line 110 of file xbot_ros.hpp.

ros::Subscriber xbot::XbotRos::motor_enable_command_subscriber
private

Definition at line 134 of file xbot_ros.hpp.

bool xbot::XbotRos::motor_enabled_
private

Definition at line 132 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::motor_state_publisher
private

Definition at line 120 of file xbot_ros.hpp.

std::string xbot::XbotRos::name
private

Definition at line 98 of file xbot_ros.hpp.

Odometry xbot::XbotRos::odometry
private

Definition at line 101 of file xbot_ros.hpp.

ros::Subscriber xbot::XbotRos::pitch_platform_command_subscriber
private

Definition at line 137 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::pitch_platform_state_publisher
private

Definition at line 118 of file xbot_ros.hpp.

int8_t xbot::XbotRos::ppd_
private

Definition at line 133 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::raw_imu_data_publisher
private

Definition at line 123 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::rear_echo_data_publisher
private

Definition at line 125 of file xbot_ros.hpp.

ros::Subscriber xbot::XbotRos::reset_odometry_subscriber
private

Definition at line 140 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::robot_state_publisher
private

Definition at line 127 of file xbot_ros.hpp.

ecl::Slot xbot::XbotRos::sensor_slot_stream_data
private

Definition at line 161 of file xbot_ros.hpp.

uint32_t xbot::XbotRos::sensor_timeout_times_
private

Definition at line 106 of file xbot_ros.hpp.

ros::Subscriber xbot::XbotRos::sound_command_subscriber
private

Definition at line 138 of file xbot_ros.hpp.

bool xbot::XbotRos::sound_enabled_
private

Definition at line 132 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::sound_state_publisher
private

Definition at line 121 of file xbot_ros.hpp.

ros::Subscriber xbot::XbotRos::velocity_command_subscriber
private

Definition at line 135 of file xbot_ros.hpp.

Xbot xbot::XbotRos::xbot
private

Definition at line 99 of file xbot_ros.hpp.

ros::Subscriber xbot::XbotRos::yaw_platform_command_subscriber
private

Definition at line 136 of file xbot_ros.hpp.

ros::Publisher xbot::XbotRos::yaw_platform_state_publisher
private

Definition at line 117 of file xbot_ros.hpp.

int8_t xbot::XbotRos::ypd_
private

Definition at line 133 of file xbot_ros.hpp.


The documentation for this class was generated from the following files:


xbot_node
Author(s): Roc, wangpeng@droid.ac.cn
autogenerated on Sat Oct 10 2020 03:28:14