gazebo_ros_kobuki.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, 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  */
29 
36 #ifndef GAZEBO_ROS_KOBUKI_H
37 #define GAZEBO_ROS_KOBUKI_H
38 
39 #include <cmath>
40 #include <cstring>
41 #include <string>
42 #include <boost/bind.hpp>
43 #include <boost/thread.hpp>
44 #include <boost/shared_ptr.hpp>
45 #include <gazebo/gazebo.hh>
46 #include <gazebo/common/common.hh>
47 #include <gazebo/common/Time.hh>
48 #if GAZEBO_MAJOR_VERSION >= 9
49  // #include <ignition/math.hh>
50  #include <ignition/math/Vector3.hh>
51  #include <ignition/math/Quaternion.hh>
52 #else
53  #include <gazebo/math/gzmath.hh>
54 #endif
55 #include <gazebo/physics/physics.hh>
56 #include <gazebo/sensors/sensors.hh>
58 #include <ros/ros.h>
59 #include <std_msgs/Empty.h>
60 #include <std_msgs/Float64.h>
61 #include <sensor_msgs/Imu.h>
62 #include <sensor_msgs/JointState.h>
63 #include <nav_msgs/Odometry.h>
64 #include <geometry_msgs/Twist.h>
65 #include <geometry_msgs/TransformStamped.h>
68 #include <kobuki_msgs/MotorPower.h>
69 #include <kobuki_msgs/CliffEvent.h>
70 #include <kobuki_msgs/BumperEvent.h>
71 
72 namespace gazebo
73 {
74 
75 enum {LEFT= 0, RIGHT=1};
76 
77 class GazeboRosKobuki : public ModelPlugin
78 {
79 public:
85  void Load(physics::ModelPtr parent, sdf::ElementPtr sdf);
87  void OnUpdate();
88 
89 private:
90  /*
91  * Methods
92  */
94  void cmdVelCB(const geometry_msgs::TwistConstPtr &msg);
96  void motorPowerCB(const kobuki_msgs::MotorPowerPtr &msg);
98  void resetOdomCB(const std_msgs::EmptyConstPtr &msg);
100  void spin();
101  // void OnContact(const std::string &name, const physics::Contact &contact); necessary?
102 
103 
104  // internal functions for load
105  void prepareMotorPower();
106  bool prepareJointState();
107  void preparePublishTf();
108  bool prepareWheelAndTorque();
109  void prepareOdom();
110  bool prepareVelocityCommand();
111  bool prepareCliffSensor();
112  bool prepareBumper();
113  bool prepareIMU();
114  void setupRosApi(std::string& model_name);
115 
116  // internal functions for update
117  void updateJointState();
118  void updateOdometry(common::Time& step_time);
119  void updateIMU();
121  void updateCliffSensor();
122  void updateBumper();
123 
124 
125  /*
126  * Parameters
127  */
131  std::string node_name_;
132 
134  std::string tf_prefix_;
136 // boost::shared_ptr<boost::thread> ros_spinner_thread_; necessary?
140  physics::ModelPtr model_;
143  sdf::ElementPtr sdf_;
145  physics::WorldPtr world_;
147  event::ConnectionPtr update_connection_;
149  common::Time prev_update_time_;
155  physics::JointPtr joints_[2];
163  sensor_msgs::JointState joint_state_;
167  common::Time last_cmd_vel_time_;
171  double wheel_speed_cmd_[2];
173  double torque_;
175  double wheel_sep_;
177  double wheel_diam_;
179  double odom_pose_[3];
181  double odom_vel_[3];
183  double *pose_cov_[36];
185  double *twist_cov_[36];
189  nav_msgs::Odometry odom_;
195  geometry_msgs::TransformStamped odom_tf_;
197  sensors::RaySensorPtr cliff_sensor_left_;
199  sensors::RaySensorPtr cliff_sensor_center_;
201  sensors::RaySensorPtr cliff_sensor_right_;
205  kobuki_msgs::CliffEvent cliff_event_;
217  sensors::ContactSensorPtr bumper_;
221  kobuki_msgs::BumperEvent bumper_event_;
235  sensors::ImuSensorPtr imu_;
237 
238  #if GAZEBO_MAJOR_VERSION >= 9
239  ignition::math::Vector3d vel_angular_;
240  #else
241  math::Vector3 vel_angular_;
242  #endif
243 
247  sensor_msgs::Imu imu_msg_;
250 
251 
252 
253 };
254 
255 } // namespace gazebo
256 
257 #endif /* GAZEBO_ROS_KOBUKI_H */
bool cliff_detected_right_
Cliff flag for the right sensor.
msg
double odom_pose_[3]
Vector for pose.
double torque_
Max. torque applied to the wheels.
GazeboRosPtr gazebo_ros_
pointer to the gazebo ros node
float cliff_detection_threshold_
measured distance in meter for detecting a cliff
double wheel_sep_
Separation between the wheels.
bool shutdown_requested_
extra thread for triggering ROS callbacks
ros::Publisher imu_pub_
ROS publisher for IMU data.
sensors::RaySensorPtr cliff_sensor_center_
Pointer to frontal cliff sensor.
void Load(physics::ModelPtr parent, sdf::ElementPtr sdf)
Called when plugin is loaded.
std::string tf_prefix_
TF Prefix.
bool bumper_center_was_pressed_
Flag for center bumper&#39;s last state.
ros::Subscriber cmd_vel_sub_
ROS subscriber for velocity commands.
bool cliff_detected_left_
Cliff flag for the left sensor.
sensors::ContactSensorPtr bumper_
Pointer to bumper sensor simulating Kobuki&#39;s left, centre and right bumper sensors.
physics::JointPtr joints_[2]
Pointers to Gazebo&#39;s joints.
bool bumper_right_was_pressed_
Flag for right bumper&#39;s last state.
sensors::ImuSensorPtr imu_
Pointer to IMU sensor model.
void OnUpdate()
Called by the world update start event.
ros::Subscriber odom_reset_sub_
ROS subscriber for reseting the odometry data.
sensor_msgs::Imu imu_msg_
ROS message for publishing IMU data.
common::Time last_cmd_vel_time_
Simulation time of the last velocity command (used for time out)
ros::Publisher joint_state_pub_
ROS publisher for joint state messages.
bool bumper_left_is_pressed_
Flag for left bumper&#39;s current state.
double wheel_diam_
Diameter of the wheels.
void setupRosApi(std::string &model_name)
bool motors_enabled_
Flag indicating if the motors are turned on or not.
kobuki_msgs::BumperEvent bumper_event_
Kobuki ROS message for bumper event.
ros::Publisher bumper_event_pub_
ROS publisher for bumper events.
math::Vector3 vel_angular_
Storage for the angular velocity reported by the IMU.
physics::ModelPtr model_
pointer to the model
double wheel_speed_cmd_[2]
Speeds of the wheels.
int floot_dist_
Maximum distance to floor.
double * pose_cov_[36]
Pointer to pose covariance matrix.
void motorPowerCB(const kobuki_msgs::MotorPowerPtr &msg)
Callback for incoming velocity commands.
bool bumper_center_is_pressed_
Flag for left bumper&#39;s current state.
ros::Publisher odom_pub_
ROS publisher for odometry messages.
void spin()
Spin method for the spinner thread.
std::string right_wheel_joint_name_
Right wheel&#39;s joint name.
void resetOdomCB(const std_msgs::EmptyConstPtr &msg)
Callback for resetting the odometry data.
double cmd_vel_timeout_
Time out for velocity commands in seconds.
double odom_vel_[3]
Vector for velocity.
ros::NodeHandle nh_
ROS node handles (relative & private)
bool cliff_detected_center_
Cliff flag for the center sensor.
bool bumper_left_was_pressed_
Flag for left bumper&#39;s last state.
std::string left_wheel_joint_name_
Left wheel&#39;s joint name.
void cmdVelCB(const geometry_msgs::TwistConstPtr &msg)
Callback for incoming velocity commands.
geometry_msgs::TransformStamped odom_tf_
TF transform for the odom frame.
std::string node_name_
node name
kobuki_msgs::CliffEvent cliff_event_
Kobuki ROS message for cliff event.
void updateOdometry(common::Time &step_time)
sensors::RaySensorPtr cliff_sensor_left_
Pointer to left cliff sensor.
common::Time prev_update_time_
Simulation time on previous update.
double * twist_cov_[36]
Pointer to twist covariance matrix.
physics::WorldPtr world_
pointer to simulated world
ros::Publisher cliff_event_pub_
ROS publisher for cliff detection events.
bool bumper_right_is_pressed_
Flag for left bumper&#39;s current state.
bool publish_tf_
Flag for (not) publish tf transform for odom -> robot.
sensor_msgs::JointState joint_state_
ROS message for joint sates.
sensors::RaySensorPtr cliff_sensor_right_
Pointer to left right sensor.
nav_msgs::Odometry odom_
ROS message for odometry data.
tf::TransformBroadcaster tf_broadcaster_
TF transform publisher for the odom frame.
ros::Subscriber motor_power_sub_
ROS subscriber for motor power commands.
event::ConnectionPtr update_connection_
pointer to the update event connection (triggers the OnUpdate callback when event update event is rec...


kobuki_gazebo_plugins
Author(s): Marcus Liebhardt
autogenerated on Mon Jun 10 2019 13:52:55