slot_callbacks.cpp
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 ** Includes
38 *****************************************************************************/
39 
41 
42 /*****************************************************************************
43  ** Namespaces
44  *****************************************************************************/
45 
46 namespace kobuki
47 {
48 
55 }
56 
57 /*****************************************************************************
58 ** Publish Sensor Stream Workers
59 *****************************************************************************/
60 
62 {
63  if ( ros::ok() ) {
65  kobuki_msgs::SensorState state;
66  CoreSensors::Data data = kobuki.getCoreSensorData();
67  state.header.stamp = ros::Time::now();
68  state.time_stamp = data.time_stamp; // firmware time stamp
69  state.bumper = data.bumper;
70  state.wheel_drop = data.wheel_drop;
71  state.cliff = data.cliff;
72  state.left_encoder = data.left_encoder;
73  state.right_encoder = data.right_encoder;
74  state.left_pwm = data.left_pwm;
75  state.right_pwm = data.right_pwm;
76  state.buttons = data.buttons;
77  state.charger = data.charger;
78  state.battery = data.battery;
79  state.over_current = data.over_current;
80 
81  Cliff::Data cliff_data = kobuki.getCliffData();
82  state.bottom = cliff_data.bottom;
83 
84  Current::Data current_data = kobuki.getCurrentData();
85  state.current = current_data.current;
86 
87  GpInput::Data gp_input_data = kobuki.getGpInputData();
88  state.digital_input = gp_input_data.digital_input;
89  for ( unsigned int i = 0; i < gp_input_data.analog_input.size(); ++i ) {
90  state.analog_input.push_back(gp_input_data.analog_input[i]);
91  }
92 
94  }
95  }
96 }
97 
99 {
100  // Take latest encoders and gyro data
101  ecl::LegacyPose2D<double> pose_update;
102  ecl::linear_algebra::Vector3d pose_update_rates;
103  kobuki.updateOdometry(pose_update, pose_update_rates);
104  kobuki.getWheelJointStates(joint_states.position[0], joint_states.velocity[0], // left wheel
105  joint_states.position[1], joint_states.velocity[1]); // right wheel
106 
107  // Update and publish odometry and joint states
108  odometry.update(pose_update, pose_update_rates, kobuki.getHeading(), kobuki.getAngularVelocity());
109 
110  if (ros::ok())
111  {
112  joint_states.header.stamp = ros::Time::now();
114  }
115 }
116 
118 {
119  if (ros::ok())
120  {
122  {
123  // Publish as shared pointer to leverage the nodelets' zero-copy pub/sub feature
124  sensor_msgs::ImuPtr msg(new sensor_msgs::Imu);
125 
126  msg->header.frame_id = "gyro_link";
127  msg->header.stamp = ros::Time::now();
128 
129  msg->orientation = tf::createQuaternionMsgFromRollPitchYaw(0.0, 0.0, kobuki.getHeading());
130 
131  // set a non-zero covariance on unused dimensions (pitch and roll); this is a requirement of robot_pose_ekf
132  // set yaw covariance as very low, to make it dominate over the odometry heading when combined
133  // 1: fill once, as its always the same; 2: using an invented value; cannot we get a realistic estimation?
134  msg->orientation_covariance[0] = DBL_MAX;
135  msg->orientation_covariance[4] = DBL_MAX;
136  msg->orientation_covariance[8] = 0.05;
137 
138  // fill angular velocity; we ignore acceleration for now
139  msg->angular_velocity.z = kobuki.getAngularVelocity();
140 
141  // angular velocity covariance; useless by now, but robot_pose_ekf's
142  // roadmap claims that it will compute velocities in the future
143  msg->angular_velocity_covariance[0] = DBL_MAX;
144  msg->angular_velocity_covariance[4] = DBL_MAX;
145  msg->angular_velocity_covariance[8] = 0.05;
146 
148  }
149  }
150 }
151 
153 {
155  {
156  // Publish as shared pointer to leverage the nodelets' zero-copy pub/sub feature
157  sensor_msgs::ImuPtr msg(new sensor_msgs::Imu);
158  ThreeAxisGyro::Data data = kobuki.getRawInertiaData();
159 
160  ros::Time now = ros::Time::now();
161  ros::Duration interval(0.01); // Time interval between each sensor reading.
162  const double digit_to_dps = 0.00875; // digit to deg/s ratio, comes from datasheet of 3d gyro[L3G4200D].
163  unsigned int length = data.followed_data_length/3;
164  for( unsigned int i=0; i<length; i++) {
165  // Each sensor reading has id, that circulate 0 to 255.
166  //msg->header.frame_id = std::string("gyro_link_" + boost::lexical_cast<std::string>((unsigned int)data.frame_id+i));
167  msg->header.frame_id = "gyro_link";
168 
169  // Update rate of 3d gyro sensor is 100 Hz, but robot's update rate is 50 Hz.
170  // So, here is some compensation.
171  // See also https://github.com/yujinrobot/kobuki/issues/216
172  msg->header.stamp = now - interval * (length-i-1);
173 
174  // Sensing axis of 3d gyro is not match with robot. It is rotated 90 degree counterclockwise about z-axis.
175  msg->angular_velocity.x = angles::from_degrees( -digit_to_dps * (short)data.data[i*3+1] );
176  msg->angular_velocity.y = angles::from_degrees( digit_to_dps * (short)data.data[i*3+0] );
177  msg->angular_velocity.z = angles::from_degrees( digit_to_dps * (short)data.data[i*3+2] );
178 
180  }
181  }
182 }
183 
185 {
186  if (ros::ok())
187  {
189  {
190  DockIR::Data data = kobuki.getDockIRData();
191 
192  // Publish as shared pointer to leverage the nodelets' zero-copy pub/sub feature
193  kobuki_msgs::DockInfraRedPtr msg(new kobuki_msgs::DockInfraRed);
194 
195  msg->header.frame_id = "dock_ir_link";
196  msg->header.stamp = ros::Time::now();
197 
198  msg->data.push_back( data.docking[0] );
199  msg->data.push_back( data.docking[1] );
200  msg->data.push_back( data.docking[2] );
201 
203  }
204  }
205 }
206 
207 /*****************************************************************************
208 ** Non Default Stream Packets
209 *****************************************************************************/
217 {
218  if (ros::ok())
219  {
220  kobuki_msgs::VersionInfoPtr msg(new kobuki_msgs::VersionInfo);
221 
222  msg->firmware = VersionInfo::toString(version_info.firmware);
223  msg->hardware = VersionInfo::toString(version_info.hardware);
224  msg->software = VersionInfo::getSoftwareVersion();
225 
226  msg->udid.resize(3);
227  msg->udid[0] = version_info.udid0;
228  msg->udid[1] = version_info.udid1;
229  msg->udid[2] = version_info.udid2;
230 
231  // Set available features mask depending on firmware and driver versions
232  if (version_info.firmware > 65536) // 1.0.0
233  {
234  msg->features |= kobuki_msgs::VersionInfo::SMOOTH_MOVE_START;
235  msg->features |= kobuki_msgs::VersionInfo::GYROSCOPE_3D_DATA;
236  }
237  if (version_info.firmware > 65792) // 1.1.0
238  {
239  // msg->features |= kobuki_msgs::VersionInfo::SOMETHING_JINCHA_FANCY;
240  }
241  // if (msg->firmware > ...
242 
244  }
245 }
246 
248 {
249  if (ros::ok())
250  {
251  kobuki_msgs::ControllerInfoPtr msg(new kobuki_msgs::ControllerInfo);
252  ControllerInfo::Data data = kobuki.getControllerInfoData();
253 
254  msg->type = data.type;
255  msg->p_gain = static_cast<float>(data.p_gain) * 0.001f;;
256  msg->i_gain = static_cast<float>(data.i_gain) * 0.001f;;
257  msg->d_gain = static_cast<float>(data.d_gain) * 0.001f;;
258 
260  }
261 }
262 
263 /*****************************************************************************
264 ** Events
265 *****************************************************************************/
266 
268 {
269  if (ros::ok())
270  {
271  kobuki_msgs::ButtonEventPtr msg(new kobuki_msgs::ButtonEvent);
272  switch(event.state) {
273  case(ButtonEvent::Pressed) : { msg->state = kobuki_msgs::ButtonEvent::PRESSED; break; }
274  case(ButtonEvent::Released) : { msg->state = kobuki_msgs::ButtonEvent::RELEASED; break; }
275  default: break;
276  }
277  switch(event.button) {
278  case(ButtonEvent::Button0) : { msg->button = kobuki_msgs::ButtonEvent::Button0; break; }
279  case(ButtonEvent::Button1) : { msg->button = kobuki_msgs::ButtonEvent::Button1; break; }
280  case(ButtonEvent::Button2) : { msg->button = kobuki_msgs::ButtonEvent::Button2; break; }
281  default: break;
282  }
284  }
285 }
286 
288 {
289  if (ros::ok())
290  {
291  kobuki_msgs::BumperEventPtr msg(new kobuki_msgs::BumperEvent);
292  switch(event.state) {
293  case(BumperEvent::Pressed) : { msg->state = kobuki_msgs::BumperEvent::PRESSED; break; }
294  case(BumperEvent::Released) : { msg->state = kobuki_msgs::BumperEvent::RELEASED; break; }
295  default: break;
296  }
297  switch(event.bumper) {
298  case(BumperEvent::Left) : { msg->bumper = kobuki_msgs::BumperEvent::LEFT; break; }
299  case(BumperEvent::Center) : { msg->bumper = kobuki_msgs::BumperEvent::CENTER; break; }
300  case(BumperEvent::Right) : { msg->bumper = kobuki_msgs::BumperEvent::RIGHT; break; }
301  default: break;
302  }
304  }
305 }
306 
308 {
309  if (ros::ok())
310  {
311  kobuki_msgs::CliffEventPtr msg(new kobuki_msgs::CliffEvent);
312  switch(event.state) {
313  case(CliffEvent::Floor) : { msg->state = kobuki_msgs::CliffEvent::FLOOR; break; }
314  case(CliffEvent::Cliff) : { msg->state = kobuki_msgs::CliffEvent::CLIFF; break; }
315  default: break;
316  }
317  switch(event.sensor) {
318  case(CliffEvent::Left) : { msg->sensor = kobuki_msgs::CliffEvent::LEFT; break; }
319  case(CliffEvent::Center) : { msg->sensor = kobuki_msgs::CliffEvent::CENTER; break; }
320  case(CliffEvent::Right) : { msg->sensor = kobuki_msgs::CliffEvent::RIGHT; break; }
321  default: break;
322  }
323  msg->bottom = event.bottom;
325  }
326 }
327 
329 {
330  if (ros::ok())
331  {
332  kobuki_msgs::WheelDropEventPtr msg(new kobuki_msgs::WheelDropEvent);
333  switch(event.state) {
334  case(WheelEvent::Dropped) : { msg->state = kobuki_msgs::WheelDropEvent::DROPPED; break; }
335  case(WheelEvent::Raised) : { msg->state = kobuki_msgs::WheelDropEvent::RAISED; break; }
336  default: break;
337  }
338  switch(event.wheel) {
339  case(WheelEvent::Left) : { msg->wheel = kobuki_msgs::WheelDropEvent::LEFT; break; }
340  case(WheelEvent::Right) : { msg->wheel = kobuki_msgs::WheelDropEvent::RIGHT; break; }
341  default: break;
342  }
344  }
345 }
346 
348 {
349  if (ros::ok())
350  {
351  kobuki_msgs::PowerSystemEventPtr msg(new kobuki_msgs::PowerSystemEvent);
352  switch(event.event) {
353  case(PowerEvent::Unplugged) :
354  { msg->event = kobuki_msgs::PowerSystemEvent::UNPLUGGED; break; }
356  { msg->event = kobuki_msgs::PowerSystemEvent::PLUGGED_TO_ADAPTER; break; }
358  { msg->event = kobuki_msgs::PowerSystemEvent::PLUGGED_TO_DOCKBASE; break; }
360  { msg->event = kobuki_msgs::PowerSystemEvent::CHARGE_COMPLETED; break; }
361  case(PowerEvent::BatteryLow) :
362  { msg->event = kobuki_msgs::PowerSystemEvent::BATTERY_LOW; break; }
364  { msg->event = kobuki_msgs::PowerSystemEvent::BATTERY_CRITICAL; break; }
365  default: break;
366  }
368  }
369 }
370 
372 {
373  if (ros::ok())
374  {
375  kobuki_msgs::DigitalInputEventPtr msg(new kobuki_msgs::DigitalInputEvent);
376  for (unsigned int i = 0; i < msg->values.size(); i++)
377  msg->values[i] = event.values[i];
379  }
380 }
381 
383 {
384  if (ros::ok())
385  {
386  kobuki_msgs::RobotStateEventPtr msg(new kobuki_msgs::RobotStateEvent);
387  switch(event.state) {
388  case(RobotEvent::Online) : { msg->state = kobuki_msgs::RobotStateEvent::ONLINE; break; }
389  case(RobotEvent::Offline) : { msg->state = kobuki_msgs::RobotStateEvent::OFFLINE; break; }
390  default: break;
391  }
392 
394  }
395 }
396 
411 {
412  if ( raw_data_command_publisher.getNumSubscribers() > 0 ) { // do not do string processing if there is no-one listening.
413  std::ostringstream ostream;
415  ostream << format(buffer); // convert to an easily readable hex string.
416  std_msgs::String s;
417  s.data = ostream.str();
418  if (ros::ok())
419  {
421  }
422  }
423 }
438 {
439  if ( raw_data_stream_publisher.getNumSubscribers() > 0 ) { // do not do string processing if there is no-one listening.
440  /*std::cout << "size: [" << buffer.size() << "], asize: [" << buffer.asize() << "]" << std::endl;
441  std::cout << "leader: " << buffer.leader << ", follower: " << buffer.follower << std::endl;
442  {
443  std::ostringstream ostream;
444  PacketFinder::BufferType::Formatter format;
445  ostream << format(buffer); // convert to an easily readable hex string.
446  //std::cout << ostream.str() << std::endl;
447  std_msgs::String s;
448  s.data = ostream.str();
449  if (ros::ok())
450  {
451  raw_data_stream_publisher.publish(s);
452  }
453  }*/
454  {
455  std::ostringstream ostream;
456  ostream << "{ " ;
457  ostream << std::setfill('0') << std::uppercase;
458  for (unsigned int i=0; i < buffer.size(); i++)
459  ostream << std::hex << std::setw(2) << static_cast<unsigned int>(buffer[i]) << " " << std::dec;
460  ostream << "}";
461  //std::cout << ostream.str() << std::endl;
462  std_msgs::StringPtr msg(new std_msgs::String);
463  msg->data = ostream.str();
464  if (ros::ok())
465  {
467  }
468  }
469  }
470 }
471 
472 void KobukiRos::publishRawControlCommand(const std::vector<short> &velocity_commands)
473 {
475  std_msgs::Int16MultiArrayPtr msg(new std_msgs::Int16MultiArray);
476  msg->data = velocity_commands;
477  if (ros::ok())
478  {
480  }
481  }
482  return;
483 }
484 
485 } // namespace kobuki
const uint32_t udid0
void publishPowerEvent(const PowerEvent &event)
msg
const uint32_t udid2
ros::Publisher wheel_event_publisher
Definition: kobuki_ros.hpp:110
void publish(const boost::shared_ptr< M > &message) const
void publishWheelEvent(const WheelEvent &event)
f
ros::Publisher robot_event_publisher
Definition: kobuki_ros.hpp:109
unsigned int size() const
std::vector< uint8_t > current
XmlRpcServer s
const uint32_t hardware
ros::Publisher raw_imu_data_publisher
Definition: kobuki_ros.hpp:108
ros::Publisher version_info_publisher
Definition: kobuki_ros.hpp:107
const uint32_t firmware
data
static std::string getSoftwareVersion()
std::vector< uint16_t > bottom
void publishButtonEvent(const ButtonEvent &event)
void publishInputEvent(const InputEvent &event)
sensor_msgs::JointState joint_states
Definition: kobuki_ros.hpp:99
enum kobuki::BumperEvent::Bumper bumper
ros::Publisher bumper_event_publisher
Definition: kobuki_ros.hpp:110
void publishCliffEvent(const CliffEvent &event)
void publishRobotEvent(const RobotEvent &event)
ros::Publisher cliff_event_publisher
Definition: kobuki_ros.hpp:110
ros::Publisher raw_data_stream_publisher
Definition: kobuki_ros.hpp:111
const uint32_t udid1
ros::Publisher controller_info_publisher
Definition: kobuki_ros.hpp:107
static std::string toString(const uint32_t &version)
ros::Publisher input_event_publisher
Definition: kobuki_ros.hpp:109
static double from_degrees(double degrees)
ros::Publisher imu_data_publisher
Definition: kobuki_ros.hpp:108
Wraps the kobuki driver in a ROS-specific library.
void publishRawDataStream(PacketFinder::BufferType &buffer)
Prints the raw data stream to a publisher.
void update(const ecl::LegacyPose2D< double > &pose_update, ecl::linear_algebra::Vector3d &pose_update_rates, double imu_heading, double imu_angular_velocity)
Definition: odometry.cpp:87
ROSCPP_DECL bool ok()
enum kobuki::ButtonEvent::Button button
ros::Publisher sensor_state_publisher
Definition: kobuki_ros.hpp:108
enum kobuki::PowerEvent::Event event
enum kobuki::WheelEvent::Wheel wheel
ros::Publisher raw_data_command_publisher
Definition: kobuki_ros.hpp:111
enum kobuki::RobotEvent::State state
void publishBumperEvent(const BumperEvent &event)
enum kobuki::WheelEvent::State state
void publishRawDataCommand(Command::Buffer &buffer)
Prints the raw data stream to a publisher.
void publishVersionInfo(const VersionInfo &version_info)
Publish fw, hw, sw version information.
enum kobuki::CliffEvent::Sensor sensor
uint32_t getNumSubscribers() const
ros::Publisher power_event_publisher
Definition: kobuki_ros.hpp:110
ros::Publisher joint_state_publisher
Definition: kobuki_ros.hpp:108
enum kobuki::CliffEvent::State state
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
static Time now()
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
ros::Publisher dock_ir_publisher
Definition: kobuki_ros.hpp:108
ros::Publisher raw_control_command_publisher
Definition: kobuki_ros.hpp:111
enum kobuki::ButtonEvent::State state
enum kobuki::BumperEvent::State state
void publishRawControlCommand(const std::vector< short > &velocity_commands)
ros::Publisher button_event_publisher
Definition: kobuki_ros.hpp:109


kobuki_node
Author(s): Daniel Stonier, Younghun Ju, Jorge Santos Simon
autogenerated on Mon Jun 10 2019 13:45:13