47 #include <boost/shared_ptr.hpp> 53 #include <std_msgs/Bool.h> 54 #include <std_msgs/Empty.h> 55 #include <std_msgs/Int16MultiArray.h> 56 #include <std_msgs/Int8.h> 57 #include <std_msgs/String.h> 58 #include <std_msgs/UInt8.h> 60 #include <sensor_msgs/Imu.h> 61 #include <sensor_msgs/JointState.h> 62 #include <sensor_msgs/Range.h> 64 #include <xbot_msgs/Battery.h> 65 #include <xbot_msgs/CoreSensor.h> 66 #include <xbot_msgs/Echo.h> 67 #include <xbot_msgs/ExtraSensor.h> 68 #include <xbot_msgs/InfraRed.h> 69 #include <ecl/sigslots.hpp> 70 #include <ecl/threads.hpp> 72 #include <xbot_msgs/RawImu.h> 73 #include <xbot_msgs/XbotState.h> 76 #include <geometry_msgs/Quaternion.h> 79 #include <xbot_talker/play.h> 88 XbotRos(std::string& node_name);
93 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
ros::Publisher rear_echo_data_publisher
ros::Subscriber velocity_command_subscriber
sensor_msgs::JointState joint_states
ros::Subscriber motor_enable_command_subscriber
ros::Subscriber yaw_platform_command_subscriber
ros::Publisher robot_state_publisher
bool first_sound_enabled_
ros::Publisher motor_state_publisher
bool led_indicate_battery
void processBaseStreamData()
ecl::Slot base_slot_stream_data
bool init(ros::NodeHandle &nh)
uint32_t base_timeout_times_
void subscribePitchPlatformCommand(const std_msgs::Int8)
ros::Subscriber sound_command_subscriber
ros::Publisher core_sensor_publisher
ecl::Slot sensor_slot_stream_data
ros::Publisher yaw_platform_state_publisher
void subscribeSoundCommand(const std_msgs::Bool)
void publishPitchPlatformState()
ros::Publisher battery_state_publisher
void publishExtraSensor()
ros::Publisher joint_state_publisher
Odometry for the xbot node.
void subscribeResetOdometry(const std_msgs::EmptyConstPtr)
Play a predefined sound (single sound or sound sequence)
ros::Subscriber pitch_platform_command_subscriber
ros::Publisher infrared_data_publisher
void advertiseTopics(ros::NodeHandle &nh)
void publishBatteryState()
ros::Publisher sound_state_publisher
void processSensorStreamData()
void publishYawPlatformState()
ros::Publisher front_echo_data_publisher
ros::Publisher pitch_platform_state_publisher
void subscribeLiftCommand(const std_msgs::UInt8)
XbotRos(std::string &node_name)
Default constructor.
ros::Publisher imu_data_publisher
void subscribeLedCommand(const std_msgs::UInt8)
ros::Publisher extra_sensor_publisher
ros::Publisher raw_imu_data_publisher
uint32_t sensor_timeout_times_
ros::Subscriber led_command_subscriber
void publishInfraredData()
void subscribeYawPlatformCommand(const std_msgs::Int8)
void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr)
ros::Subscriber reset_odometry_subscriber
Function loading component of a callback system.
void subscribeTopics(ros::NodeHandle &nh)
void subscribeMotorEnableCommand(const std_msgs::Bool)