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/xbot_node/xbot_ros.hpp"
41 
42 /*****************************************************************************
43  ** Namespaces
44  *****************************************************************************/
45 
46 namespace xbot
47 {
48 
49 /*****************************************************************************
50  ** Implementation
51  *****************************************************************************/
52 
53 void XbotRos::subscribeVelocityCommand(const geometry_msgs::TwistConstPtr msg)
54 {
55  if (xbot.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_ERROR_STREAM("Xbot : velocity command received [" << msg->linear.x << "],[" << msg->angular.z << "]");
62  xbot.setBaseControl(msg->linear.x, msg->angular.z);
64  }
65  return;
66 }
67 
68 
76 void XbotRos::subscribeResetOdometry(const std_msgs::EmptyConstPtr /* msg */)
77 {
78  ROS_INFO_STREAM("Xbot : Resetting the odometry. [" << name << "].");
79  joint_states.position[0] = 0.0; // wheel_left
80  joint_states.velocity[0] = 0.0;
81  joint_states.position[1] = 0.0; // wheel_right
82  joint_states.velocity[1] = 0.0;
83  joint_states.position[2] = 0.0; // wheel_left
84  joint_states.velocity[2] = 0.0;
85  joint_states.position[3] = 0.0; // wheel_right
86  joint_states.velocity[3] = 0.0;
88  xbot.resetOdometry();
89  return;
90 }
91 void XbotRos::subscribeMotorEnableCommand(const std_msgs::Bool msg)
92 {
93  motor_enabled_ = msg.data;
94 }
95 
96 void XbotRos::subscribeLiftCommand(const std_msgs::UInt8 msg)
97 {
98  xbot.setLiftControl(msg.data);
99 }
100 
101 void XbotRos::subscribeYawPlatformCommand(const std_msgs::Int8 msg)
102 {
103  ypd_ = msg.data;
104 
105 }
106 void XbotRos::subscribePitchPlatformCommand(const std_msgs::Int8 msg)
107 {
108  ppd_=msg.data;
109 }
110 void XbotRos::subscribeLedCommand(const std_msgs::UInt8 msg)
111 {
112  xbot.setLedControl(msg.data);
113 }
114 
115 void XbotRos::subscribeSoundCommand(const std_msgs::Bool msg)
116 {
117  sound_enabled_ = msg.data;
118 }
119 
120 
121 
122 } // namespace xbot
sensor_msgs::JointState joint_states
Definition: xbot_ros.hpp:100
void resetOdometry()
Definition: odometry.hpp:46
bool sound_enabled_
Definition: xbot_ros.hpp:132
void subscribePitchPlatformCommand(const std_msgs::Int8)
std::string name
Definition: xbot_ros.hpp:98
void subscribeSoundCommand(const std_msgs::Bool)
void subscribeResetOdometry(const std_msgs::EmptyConstPtr)
Play a predefined sound (single sound or sound sequence)
void resetTimeout()
Definition: odometry.hpp:48
#define ROS_INFO_STREAM(args)
void subscribeLiftCommand(const std_msgs::UInt8)
void subscribeLedCommand(const std_msgs::UInt8)
bool motor_enabled_
Definition: xbot_ros.hpp:132
Odometry odometry
Definition: xbot_ros.hpp:101
void subscribeYawPlatformCommand(const std_msgs::Int8)
void subscribeVelocityCommand(const geometry_msgs::TwistConstPtr)
void subscribeMotorEnableCommand(const std_msgs::Bool)


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