xbot_ros.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Yujin Robot.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Yujin Robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
36 /*****************************************************************************
37  ** Ifdefs
38  *****************************************************************************/
39 
40 #ifndef XBOT_ROS_HPP_
41 #define XBOT_ROS_HPP_
42 
43 /*****************************************************************************
44  ** Includes
45  *****************************************************************************/
46 
47 #include <boost/shared_ptr.hpp>
48 #include <string>
49 
50 #include <angles/angles.h>
51 #include <ros/ros.h>
52 
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>
59 
60 #include <sensor_msgs/Imu.h>
61 #include <sensor_msgs/JointState.h>
62 #include <sensor_msgs/Range.h>
63 
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>
71 
72 #include <xbot_msgs/RawImu.h>
73 #include <xbot_msgs/XbotState.h>
74 #include <xbot_driver/xbot.hpp>
75 
76 #include <geometry_msgs/Quaternion.h>
77 #include "odometry.hpp"
78 
79 #include <xbot_talker/play.h>
80 
81 /*****************************************************************************
82  ** Namespaces
83  *****************************************************************************/
84 
85 namespace xbot {
86 class XbotRos {
87  public:
88  XbotRos(std::string& node_name);
89  ~XbotRos();
90  bool init(ros::NodeHandle& nh);
91  bool update();
92 
93  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
94  private:
95  /*********************
96  ** Variables
97  **********************/
98  std::string name; // name of the ROS node
100  sensor_msgs::JointState joint_states;
102  bool cmd_vel_timed_out_; // stops warning spam when cmd_vel flags as timed
103  // out more than once in a row
104  uint32_t base_timeout_times_; // stops warning spam when serial connection
105  // timed out more than once in a row
107 
111 
112  /*********************
113  ** Ros Publishers
114  **********************/
128 
129  /*********************
130  ** Ros Subscribers
131  **********************/
141 
144 
145  /*********************
146  ** Ros Callbacks
147  **********************/
148  void subscribeMotorEnableCommand(const std_msgs::Bool);
149  void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr);
150  void subscribeYawPlatformCommand(const std_msgs::Int8);
151  void subscribePitchPlatformCommand(const std_msgs::Int8);
152  void subscribeSoundCommand(const std_msgs::Bool);
153  void subscribeLedCommand(const std_msgs::UInt8);
154  void subscribeLiftCommand(const std_msgs::UInt8);
155  void subscribeResetOdometry(const std_msgs::EmptyConstPtr);
156 
157  /*********************
158  ** SigSlots
159  **********************/
162 
163  /*********************
164  ** Base Slot Callbacks
165  **********************/
166  void processBaseStreamData();
167  void publishWheelState();
168  void publishCoreSensor();
169  void publishEchoData();
170  void publishInfraredData();
171  void publishBatteryState();
172  void publishMotorState();
173 
174  /*********************
175  ** Sensor Slot Callbacks
176  **********************/
178  void publishExtraSensor();
181  void publishSoundState();
182  void publishInertia();
183  void publishRawInertia();
184  void publishRobotState();
185 };
186 
187 } // namespace xbot
188 
189 #endif /* XBOT_ROS_HPP_ */
ros::Publisher rear_echo_data_publisher
Definition: xbot_ros.hpp:125
ros::Subscriber velocity_command_subscriber
Definition: xbot_ros.hpp:135
sensor_msgs::JointState joint_states
Definition: xbot_ros.hpp:100
ros::Subscriber motor_enable_command_subscriber
Definition: xbot_ros.hpp:134
ros::Subscriber yaw_platform_command_subscriber
Definition: xbot_ros.hpp:136
ros::Publisher robot_state_publisher
Definition: xbot_ros.hpp:127
bool first_sound_enabled_
Definition: xbot_ros.hpp:109
ros::Publisher motor_state_publisher
Definition: xbot_ros.hpp:120
bool led_indicate_battery
Definition: xbot_ros.hpp:108
void processBaseStreamData()
ecl::Slot base_slot_stream_data
Definition: xbot_ros.hpp:160
void publishWheelState()
bool sound_enabled_
Definition: xbot_ros.hpp:132
void publishRawInertia()
bool init(ros::NodeHandle &nh)
Definition: xbot_ros.cpp:87
uint32_t base_timeout_times_
Definition: xbot_ros.hpp:104
File comment.
void subscribePitchPlatformCommand(const std_msgs::Int8)
ros::Subscriber sound_command_subscriber
Definition: xbot_ros.hpp:138
ros::Publisher core_sensor_publisher
Definition: xbot_ros.hpp:115
std::string name
Definition: xbot_ros.hpp:98
ecl::Slot sensor_slot_stream_data
Definition: xbot_ros.hpp:161
ros::Publisher yaw_platform_state_publisher
Definition: xbot_ros.hpp:117
bool update()
Definition: xbot_ros.cpp:245
void subscribeSoundCommand(const std_msgs::Bool)
void publishSoundState()
void publishPitchPlatformState()
ros::Publisher battery_state_publisher
Definition: xbot_ros.hpp:119
void publishExtraSensor()
ros::Publisher joint_state_publisher
Definition: xbot_ros.hpp:126
Odometry for the xbot node.
Definition: odometry.hpp:39
void subscribeResetOdometry(const std_msgs::EmptyConstPtr)
Play a predefined sound (single sound or sound sequence)
unsigned int uint32_t
void publishMotorState()
bool cmd_vel_timed_out_
Definition: xbot_ros.hpp:102
ros::Subscriber pitch_platform_command_subscriber
Definition: xbot_ros.hpp:137
signed char int8_t
ros::Publisher infrared_data_publisher
Definition: xbot_ros.hpp:124
void advertiseTopics(ros::NodeHandle &nh)
Definition: xbot_ros.cpp:295
void publishBatteryState()
ros::Publisher sound_state_publisher
Definition: xbot_ros.hpp:121
void processSensorStreamData()
void publishYawPlatformState()
ros::Publisher front_echo_data_publisher
Definition: xbot_ros.hpp:125
ros::Publisher pitch_platform_state_publisher
Definition: xbot_ros.hpp:118
void publishRobotState()
void publishCoreSensor()
void subscribeLiftCommand(const std_msgs::UInt8)
XbotRos(std::string &node_name)
Default constructor.
Definition: xbot_ros.cpp:60
ros::Publisher imu_data_publisher
Definition: xbot_ros.hpp:122
void subscribeLedCommand(const std_msgs::UInt8)
ros::Publisher extra_sensor_publisher
Definition: xbot_ros.hpp:116
ros::Publisher raw_imu_data_publisher
Definition: xbot_ros.hpp:123
uint32_t sensor_timeout_times_
Definition: xbot_ros.hpp:106
bool motor_enabled_
Definition: xbot_ros.hpp:132
ros::Subscriber led_command_subscriber
Definition: xbot_ros.hpp:139
void publishInfraredData()
Odometry odometry
Definition: xbot_ros.hpp:101
void subscribeYawPlatformCommand(const std_msgs::Int8)
void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr)
ros::Subscriber reset_odometry_subscriber
Definition: xbot_ros.hpp:140
Function loading component of a callback system.
Definition: slot.hpp:48
void subscribeTopics(ros::NodeHandle &nh)
Definition: xbot_ros.cpp:337
void subscribeMotorEnableCommand(const std_msgs::Bool)


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