00001 /* 00002 * Copyright (c) 2013, Yujin Robot. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of Yujin Robot nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00036 #ifndef GAZEBO_ROS_KOBUKI_H 00037 #define GAZEBO_ROS_KOBUKI_H 00038 00039 #include <string> 00040 #include <boost/thread.hpp> 00041 #include <boost/shared_ptr.hpp> 00042 #include <gazebo/gazebo.hh> 00043 #include <gazebo/common/common.hh> 00044 #include <gazebo/common/Time.hh> 00045 #include <gazebo/math/gzmath.hh> 00046 #include <gazebo/physics/physics.hh> 00047 #include <gazebo/sensors/sensors.hh> 00048 #include <ros/ros.h> 00049 #include <std_msgs/Empty.h> 00050 #include <std_msgs/Float64.h> 00051 #include <sensor_msgs/Imu.h> 00052 #include <nav_msgs/Odometry.h> 00053 #include <geometry_msgs/Twist.h> 00054 #include <geometry_msgs/TransformStamped.h> 00055 #include <tf/transform_broadcaster.h> 00056 #include <kobuki_msgs/MotorPower.h> 00057 #include <kobuki_msgs/CliffEvent.h> 00058 #include <kobuki_msgs/BumperEvent.h> 00059 00060 namespace gazebo 00061 { 00062 00063 class GazeboRosKobuki : public ModelPlugin 00064 { 00065 public: 00067 GazeboRosKobuki(); 00069 ~GazeboRosKobuki(); 00071 void Load(physics::ModelPtr parent, sdf::ElementPtr sdf); 00073 void OnUpdate(); 00074 00075 private: 00076 /* 00077 * Methods 00078 */ 00080 void cmdVelCB(const geometry_msgs::TwistConstPtr &msg); 00082 void motorPowerCB(const kobuki_msgs::MotorPowerPtr &msg); 00084 void resetOdomCB(const std_msgs::EmptyConstPtr &msg); 00086 void spin(); 00087 // void OnContact(const std::string &name, const physics::Contact &contact); necessary? 00088 00089 /* 00090 * Parameters 00091 */ 00093 ros::NodeHandle nh_, nh_priv_; 00095 std::string node_name_; 00097 // boost::shared_ptr<boost::thread> ros_spinner_thread_; necessary? 00099 bool shutdown_requested_; 00101 physics::ModelPtr model_; 00103 physics::WorldPtr world_; 00105 event::ConnectionPtr update_connection_; 00107 common::Time prev_update_time_; 00109 ros::Subscriber motor_power_sub_; 00111 bool motors_enabled_; 00113 physics::JointPtr joints_[2]; 00115 std::string left_wheel_joint_name_; 00117 std::string right_wheel_joint_name_; 00119 ros::Publisher joint_state_pub_; 00121 sensor_msgs::JointState joint_state_; 00123 ros::Subscriber cmd_vel_sub_; 00125 common::Time last_cmd_vel_time_; 00127 double cmd_vel_timeout_; 00129 double wheel_speed_cmd_[2]; 00131 double torque_; 00133 double wheel_sep_; 00135 double wheel_diam_; 00137 double odom_pose_[3]; 00139 double odom_vel_[3]; 00141 double *pose_cov_[36]; 00143 double *twist_cov_[36]; 00145 ros::Publisher odom_pub_; 00147 nav_msgs::Odometry odom_; 00149 bool publish_tf_; 00151 tf::TransformBroadcaster tf_broadcaster_; 00153 geometry_msgs::TransformStamped odom_tf_; 00155 sensors::RaySensorPtr cliff_sensor_left_; 00157 sensors::RaySensorPtr cliff_sensor_center_; 00159 sensors::RaySensorPtr cliff_sensor_right_; 00161 ros::Publisher cliff_event_pub_; 00163 kobuki_msgs::CliffEvent cliff_event_; 00165 bool cliff_detected_left_; 00167 bool cliff_detected_center_; 00169 bool cliff_detected_right_; 00171 float cliff_detection_threshold_; 00173 int floot_dist_; 00175 sensors::ContactSensorPtr bumper_; 00177 ros::Publisher bumper_event_pub_; 00179 kobuki_msgs::BumperEvent bumper_event_; 00181 bool bumper_left_was_pressed_; 00183 bool bumper_center_was_pressed_; 00185 bool bumper_right_was_pressed_; 00187 bool bumper_left_is_pressed_; 00189 bool bumper_center_is_pressed_; 00191 bool bumper_right_is_pressed_; 00193 sensors::ImuSensorPtr imu_; 00195 math::Vector3 vel_angular_; 00197 ros::Publisher imu_pub_; 00199 sensor_msgs::Imu imu_msg_; 00201 ros::Subscriber odom_reset_sub_; 00202 }; 00203 00204 } // namespace gazebo 00205 00206 #endif /* GAZEBO_ROS_KOBUKI_H */