subscriber_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 
40 #include "../../include/kobuki_node/kobuki_ros.hpp"
41 
42 /*****************************************************************************
43  ** Namespaces
44  *****************************************************************************/
45 
46 namespace kobuki
47 {
48 
49 /*****************************************************************************
50  ** Implementation
51  *****************************************************************************/
52 
53 void KobukiRos::subscribeVelocityCommand(const geometry_msgs::TwistConstPtr msg)
54 {
55  if (kobuki.isEnabled())
56  {
57  // For now assuming this is in the robot frame, but probably this
58  // should be global frame and require a transform
59  //double vx = msg->linear.x; // in (m/s)
60  //double wz = msg->angular.z; // in (rad/s)
61  ROS_DEBUG_STREAM("Kobuki : velocity command received [" << msg->linear.x << "],[" << msg->angular.z << "]");
62  kobuki.setBaseControl(msg->linear.x, msg->angular.z);
64  }
65  return;
66 }
67 
68 
69 void KobukiRos::subscribeLed1Command(const kobuki_msgs::LedConstPtr msg)
70 {
71  switch( msg->value ) {
72  case kobuki_msgs::Led::GREEN: kobuki.setLed(Led1, Green ); break;
73  case kobuki_msgs::Led::ORANGE: kobuki.setLed(Led1, Orange ); break;
74  case kobuki_msgs::Led::RED: kobuki.setLed(Led1, Red ); break;
75  case kobuki_msgs::Led::BLACK: kobuki.setLed(Led1, Black ); break;
76  default: ROS_WARN_STREAM("Kobuki : led 1 command value invalid."); break;
77  }
78  return;
79 }
80 
81 void KobukiRos::subscribeLed2Command(const kobuki_msgs::LedConstPtr msg)
82 {
83  switch( msg->value ) {
84  case kobuki_msgs::Led::GREEN: kobuki.setLed(Led2, Green ); break;
85  case kobuki_msgs::Led::ORANGE: kobuki.setLed(Led2, Orange ); break;
86  case kobuki_msgs::Led::RED: kobuki.setLed(Led2, Red ); break;
87  case kobuki_msgs::Led::BLACK: kobuki.setLed(Led2, Black ); break;
88  default: ROS_WARN_STREAM("Kobuki : led 2 command value invalid."); break;
89  }
90  return;
91 }
92 
93 void KobukiRos::subscribeDigitalOutputCommand(const kobuki_msgs::DigitalOutputConstPtr msg)
94 {
95  DigitalOutput digital_output;
96  for ( unsigned int i = 0; i < 4; ++i ) {
97  digital_output.values[i] = msg->values[i];
98  digital_output.mask[i] = msg->mask[i];
99  }
100  kobuki.setDigitalOutput(digital_output);
101  return;
102 }
103 
104 void KobukiRos::subscribeExternalPowerCommand(const kobuki_msgs::ExternalPowerConstPtr msg)
105 {
106  // Validate message
107  if (!((msg->source == kobuki_msgs::ExternalPower::PWR_3_3V1A) ||
108  (msg->source == kobuki_msgs::ExternalPower::PWR_5V1A) ||
109  (msg->source == kobuki_msgs::ExternalPower::PWR_12V5A) ||
110  (msg->source == kobuki_msgs::ExternalPower::PWR_12V1_5A)))
111  {
112  ROS_ERROR_STREAM("Kobuki : Power source " << (unsigned int)msg->source << " does not exist! [" << name << "].");
113  return;
114  }
115  if (!((msg->state == kobuki_msgs::ExternalPower::OFF) ||
116  (msg->state == kobuki_msgs::ExternalPower::ON)))
117  {
118  ROS_ERROR_STREAM("Kobuki : Power source state "
119  << (unsigned int)msg->state << " does not exist! [" << name << "].");
120  return;
121  }
122 
123  DigitalOutput digital_output;
124  for ( unsigned int i = 0; i < 4; ++i )
125  {
126  if (i == msg->source)
127  {
128  if (msg->state)
129  {
130  digital_output.values[i] = true; // turn source on
131  ROS_INFO_STREAM("Kobuki : Turning on external power source "
132  << (unsigned int)msg->source << ". [" << name << "].");
133  }
134  else
135  {
136  digital_output.values[i] = false; // turn source off
137  ROS_INFO_STREAM("Kobuki : Turning off external power source "
138  << (unsigned int)msg->source << ". [" << name << "].");
139  }
140  digital_output.mask[i] = true; // change source state
141  }
142  else
143  {
144  digital_output.values[i] = false; // values doesn't matter here, since mask is set false, what means ignoring
145  digital_output.mask[i] = false;
146  }
147  }
148  kobuki.setExternalPower(digital_output);
149  return;
150 }
151 
155 void KobukiRos::subscribeSoundCommand(const kobuki_msgs::SoundConstPtr msg)
156 {
157  if ( msg->value == kobuki_msgs::Sound::ON )
158  {
159  kobuki.playSoundSequence(On);
160  }
161  else if ( msg->value == kobuki_msgs::Sound::OFF )
162  {
163  kobuki.playSoundSequence(Off);
164  }
165  else if ( msg->value == kobuki_msgs::Sound::RECHARGE )
166  {
167  kobuki.playSoundSequence(Recharge);
168  }
169  else if ( msg->value == kobuki_msgs::Sound::BUTTON )
170  {
171  kobuki.playSoundSequence(Button);
172  }
173  else if ( msg->value == kobuki_msgs::Sound::ERROR )
174  {
175  kobuki.playSoundSequence(Error);
176  }
177  else if ( msg->value == kobuki_msgs::Sound::CLEANINGSTART )
178  {
179  kobuki.playSoundSequence(CleaningStart);
180  }
181  else if ( msg->value == kobuki_msgs::Sound::CLEANINGEND )
182  {
183  kobuki.playSoundSequence(CleaningEnd);
184  }
185  else
186  {
187  ROS_WARN_STREAM("Kobuki : Invalid sound command! There is no sound stored for value '" << msg->value << "'.");
188  }
189  return;
190 }
191 
195 void KobukiRos::subscribeResetOdometry(const std_msgs::EmptyConstPtr /* msg */)
196 {
197  ROS_INFO_STREAM("Kobuki : Resetting the odometry. [" << name << "].");
198  joint_states.position[0] = 0.0; // wheel_left
199  joint_states.velocity[0] = 0.0;
200  joint_states.position[1] = 0.0; // wheel_right
201  joint_states.velocity[1] = 0.0;
203  kobuki.resetOdometry();
204  return;
205 }
206 
207 void KobukiRos::subscribeMotorPower(const kobuki_msgs::MotorPowerConstPtr msg)
208 {
209  if (msg->state == kobuki_msgs::MotorPower::ON)
210  {
211  ROS_INFO_STREAM("Kobuki : Firing up the motors. [" << name << "]");
212  kobuki.enable();
214  }
215  else if (msg->state == kobuki_msgs::MotorPower::OFF)
216  {
217  kobuki.disable();
218  ROS_INFO_STREAM("Kobuki : Shutting down the motors. [" << name << "]");
220  }
221  else
222  {
223  ROS_ERROR_STREAM("Kobuki : Motor power command specifies unknown state '" << (unsigned int)msg->state
224  << "'. [" << name << "]");
225  }
226 }
227 
228 void KobukiRos::subscribeControllerInfoCommand(const kobuki_msgs::ControllerInfoConstPtr msg)
229 {
230  if( msg->p_gain < 0.0f || msg->i_gain < 0.0f || msg->d_gain < 0.0f) {
231  ROS_ERROR_STREAM("Kobuki : All controller gains should be positive. [" << name << "]");
232  return;
233  }
234  kobuki.setControllerGain(msg->type,
235  static_cast<unsigned int>(msg->p_gain*1000.0f),
236  static_cast<unsigned int>(msg->i_gain*1000.0f),
237  static_cast<unsigned int>(msg->d_gain*1000.0f));
238  return;
239 }
240 
241 } // namespace kobuki
void resetOdometry()
Definition: odometry.hpp:46
void subscribeMotorPower(const kobuki_msgs::MotorPowerConstPtr msg)
void subscribeDigitalOutputCommand(const kobuki_msgs::DigitalOutputConstPtr)
void resetTimeout()
Definition: odometry.hpp:48
sensor_msgs::JointState joint_states
Definition: kobuki_ros.hpp:99
void subscribeControllerInfoCommand(const kobuki_msgs::ControllerInfoConstPtr msg)
void subscribeSoundCommand(const kobuki_msgs::SoundConstPtr)
Play a predefined sound (single sound or sound sequence)
void subscribeLed1Command(const kobuki_msgs::LedConstPtr)
void subscribeExternalPowerCommand(const kobuki_msgs::ExternalPowerConstPtr)
void subscribeLed2Command(const kobuki_msgs::LedConstPtr)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
#define ROS_INFO_STREAM(args)
std::string name
Definition: kobuki_ros.hpp:97
#define ROS_ERROR_STREAM(args)
void subscribeResetOdometry(const std_msgs::EmptyConstPtr)
Reset the odometry variables.
void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr)


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