Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00036 #include "kobuki_gazebo_plugins/gazebo_ros_kobuki.h"
00037
00038 namespace gazebo
00039 {
00040
00041
00042
00043
00044 void GazeboRosKobuki::prepareMotorPower() {
00045 motors_enabled_ = true;
00046 }
00047
00048
00049
00050
00051 bool GazeboRosKobuki::prepareJointState()
00052 {
00053 if (sdf_->HasElement("left_wheel_joint_name"))
00054 {
00055 left_wheel_joint_name_ = sdf_->GetElement("left_wheel_joint_name")->Get<std::string>();
00056 }
00057 else
00058 {
00059 ROS_ERROR_STREAM("Couldn't find left wheel joint in the model description!"
00060 << " Did you specify the correct joint name?" << " [" << node_name_ <<"]");
00061 return false;
00062 }
00063 if (sdf_->HasElement("right_wheel_joint_name"))
00064 {
00065 right_wheel_joint_name_ = sdf_->GetElement("right_wheel_joint_name")->Get<std::string>();
00066 }
00067 else
00068 {
00069 ROS_ERROR_STREAM("Couldn't find right wheel joint in the model description!"
00070 << " Did you specify the correct joint name?" << " [" << node_name_ <<"]");
00071 return false;
00072 }
00073 joints_[LEFT] = model_->GetJoint(left_wheel_joint_name_);
00074 joints_[RIGHT] = model_->GetJoint(right_wheel_joint_name_);
00075 if (!joints_[LEFT] || !joints_[RIGHT])
00076 {
00077 ROS_ERROR_STREAM("Couldn't find specified wheel joints in the model! [" << node_name_ <<"]");
00078 return false;
00079 }
00080 joint_state_.header.frame_id = "Joint States";
00081 joint_state_.name.push_back(left_wheel_joint_name_);
00082 joint_state_.position.push_back(0);
00083 joint_state_.velocity.push_back(0);
00084 joint_state_.effort.push_back(0);
00085 joint_state_.name.push_back(right_wheel_joint_name_);
00086 joint_state_.position.push_back(0);
00087 joint_state_.velocity.push_back(0);
00088 joint_state_.effort.push_back(0);
00089
00090 return true;
00091 }
00092
00093
00094
00095
00096 void GazeboRosKobuki::preparePublishTf()
00097 {
00098 if (sdf_->HasElement("publish_tf"))
00099 {
00100 publish_tf_ = sdf_->GetElement("publish_tf")->Get<bool>();
00101 if (publish_tf_)
00102 {
00103 ROS_INFO_STREAM("Will publish tf." << " [" << node_name_ <<"]");
00104 }
00105 else
00106 {
00107 ROS_INFO_STREAM("Won't publish tf." << " [" << node_name_ <<"]");
00108 }
00109 }
00110 else
00111 {
00112 publish_tf_ = false;
00113 ROS_INFO_STREAM("Couldn't find the 'publish tf' parameter in the model description."
00114 << " Won't publish tf." << " [" << node_name_ <<"]");
00115 }
00116 }
00117
00118 bool GazeboRosKobuki::prepareWheelAndTorque()
00119 {
00120 if (sdf_->HasElement("wheel_separation"))
00121 {
00122 wheel_sep_ = sdf_->GetElement("wheel_separation")->Get<double>();
00123 }
00124 else
00125 {
00126 ROS_ERROR_STREAM("Couldn't find the wheel separation parameter in the model description!"
00127 << " Did you specify it?" << " [" << node_name_ <<"]");
00128 return false;
00129 }
00130 if (sdf_->HasElement("wheel_diameter"))
00131 {
00132 wheel_diam_ = sdf_->GetElement("wheel_diameter")->Get<double>();
00133 }
00134 else
00135 {
00136 ROS_ERROR_STREAM("Couldn't find the wheel diameter parameter in the model description!"
00137 << " Did you specify it?" << " [" << node_name_ <<"]");
00138 return false;
00139 }
00140 if (sdf_->HasElement("torque"))
00141 {
00142 torque_ = sdf_->GetElement("torque")->Get<double>();
00143 }
00144 else
00145 {
00146 ROS_ERROR_STREAM("Couldn't find the torque parameter in the model description!"
00147 << " Did you specify it?" << " [" << node_name_ <<"]");
00148 return false;
00149 }
00150 return true;
00151 }
00152
00153 void GazeboRosKobuki::prepareOdom()
00154 {
00155 odom_pose_[0] = 0.0;
00156 odom_pose_[1] = 0.0;
00157 odom_pose_[2] = 0.0;
00158 }
00159
00160
00161
00162
00163 bool GazeboRosKobuki::prepareVelocityCommand()
00164 {
00165 if (sdf_->HasElement("velocity_command_timeout"))
00166 {
00167 cmd_vel_timeout_ = sdf_->GetElement("velocity_command_timeout")->Get<double>();
00168 }
00169 else
00170 {
00171 ROS_ERROR_STREAM("Couldn't find the wheel separation parameter in the model description!"
00172 << " Did you specify it?" << " [" << node_name_ <<"]");
00173 return false;
00174 }
00175 last_cmd_vel_time_ = world_->GetSimTime();
00176 return true;
00177 }
00178
00179 bool GazeboRosKobuki::prepareCliffSensor()
00180 {
00181
00182
00183
00184 std::string cliff_sensor_left_name, cliff_sensor_center_name, cliff_sensor_right_name;
00185 if (sdf_->HasElement("cliff_sensor_left_name"))
00186 {
00187 cliff_sensor_left_name = sdf_->GetElement("cliff_sensor_left_name")->Get<std::string>();
00188 }
00189 else
00190 {
00191 ROS_ERROR_STREAM("Couldn't find the name of left cliff sensor in the model description!"
00192 << " Did you specify it?" << " [" << node_name_ <<"]");
00193 return false;
00194 }
00195 if (sdf_->HasElement("cliff_sensor_center_name"))
00196 {
00197 cliff_sensor_center_name = sdf_->GetElement("cliff_sensor_center_name")->Get<std::string>();
00198 }
00199 else
00200 {
00201 ROS_ERROR_STREAM("Couldn't find the name of frontal cliff sensor in the model description!"
00202 << " Did you specify it?" << " [" << node_name_ <<"]");
00203 return false;
00204 }
00205 if (sdf_->HasElement("cliff_sensor_right_name"))
00206 {
00207 cliff_sensor_right_name = sdf_->GetElement("cliff_sensor_right_name")->Get<std::string>();
00208 }
00209 else
00210 {
00211 ROS_ERROR_STREAM("Couldn't find the name of right cliff sensor in the model description!"
00212 << " Did you specify it?" << " [" << node_name_ <<"]");
00213 return false;
00214 }
00215 cliff_sensor_left_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
00216 sensors::SensorManager::Instance()->GetSensor(cliff_sensor_left_name));
00217 cliff_sensor_center_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
00218 sensors::SensorManager::Instance()->GetSensor(cliff_sensor_center_name));
00219 cliff_sensor_right_ = boost::dynamic_pointer_cast<sensors::RaySensor>(
00220 sensors::SensorManager::Instance()->GetSensor(cliff_sensor_right_name));
00221 if (!cliff_sensor_left_)
00222 {
00223 ROS_ERROR_STREAM("Couldn't find the left cliff sensor in the model! [" << node_name_ <<"]");
00224 return false;
00225 }
00226 if (!cliff_sensor_center_)
00227 {
00228 ROS_ERROR_STREAM("Couldn't find the center cliff sensor in the model! [" << node_name_ <<"]");
00229 return false;
00230 }
00231 if (!cliff_sensor_right_)
00232 {
00233 ROS_ERROR_STREAM("Couldn't find the right cliff sensor in the model! [" << node_name_ <<"]");
00234 return false;
00235 }
00236 if (sdf_->HasElement("cliff_detection_threshold"))
00237 {
00238 cliff_detection_threshold_ = sdf_->GetElement("cliff_detection_threshold")->Get<double>();
00239 }
00240 else
00241 {
00242 ROS_ERROR_STREAM("Couldn't find the cliff detection threshold parameter in the model description!"
00243 << " Did you specify it?" << " [" << node_name_ <<"]");
00244 return false;
00245 }
00246 cliff_sensor_left_->SetActive(true);
00247 cliff_sensor_center_->SetActive(true);
00248 cliff_sensor_right_->SetActive(true);
00249
00250 return true;
00251 }
00252
00253
00254
00255
00256
00257 bool GazeboRosKobuki::prepareBumper()
00258 {
00259 std::string bumper_name;
00260 if (sdf_->HasElement("bumper_name"))
00261 {
00262 bumper_name = sdf_->GetElement("bumper_name")->Get<std::string>();
00263 }
00264 else
00265 {
00266 ROS_ERROR_STREAM("Couldn't find the name of bumper sensor in the model description!"
00267 << " Did you specify it?" << " [" << node_name_ <<"]");
00268 return false;
00269 }
00270 bumper_ = boost::dynamic_pointer_cast<sensors::ContactSensor>(
00271 sensors::SensorManager::Instance()->GetSensor(bumper_name));
00272 if (!bumper_)
00273 {
00274 ROS_ERROR_STREAM("Couldn't find the bumpers in the model! [" << node_name_ <<"]");
00275 return false;
00276 }
00277 bumper_->SetActive(true);
00278 return true;
00279 }
00280
00281
00282
00283
00284 bool GazeboRosKobuki::prepareIMU()
00285 {
00286 std::string imu_name;
00287 if (sdf_->HasElement("imu_name"))
00288 {
00289 imu_name = sdf_->GetElement("imu_name")->Get<std::string>();
00290 }
00291 else
00292 {
00293 ROS_ERROR_STREAM("Couldn't find the name of IMU sensor in the model description!"
00294 << " Did you specify it?" << " [" << node_name_ <<"]");
00295 return false;
00296 }
00297 imu_ = boost::dynamic_pointer_cast<sensors::ImuSensor>(
00298 sensors::get_sensor(world_->GetName()+"::"+node_name_+"::base_footprint::"+imu_name));
00299 if (!imu_)
00300 {
00301 ROS_ERROR_STREAM("Couldn't find the IMU in the model! [" << node_name_ <<"]");
00302 return false;
00303 }
00304 imu_->SetActive(true);
00305 return true;
00306 }
00307
00308 void GazeboRosKobuki::setupRosApi(std::string& model_name)
00309 {
00310 std::string base_prefix;
00311 gazebo_ros_->node()->param("base_prefix", base_prefix, std::string("mobile_base"));
00312
00313
00314
00315
00316 std::string joint_states_topic = "joint_states";
00317 joint_state_pub_ = gazebo_ros_->node()->advertise<sensor_msgs::JointState>(joint_states_topic, 1);
00318 ROS_INFO("%s: Advertise joint_states[%s]!", gazebo_ros_->info(), joint_states_topic.c_str());
00319
00320
00321 std::string odom_topic = "odom";
00322 odom_pub_ = gazebo_ros_->node()->advertise<nav_msgs::Odometry>(odom_topic, 1);
00323 ROS_INFO("%s: Advertise Odometry[%s]!", gazebo_ros_->info(), odom_topic.c_str());
00324
00325
00326
00327
00328 std::string motor_power_topic = base_prefix + "/commands/motor_power";
00329 motor_power_sub_ = gazebo_ros_->node()->subscribe(motor_power_topic, 10, &GazeboRosKobuki::motorPowerCB, this);
00330 ROS_INFO("%s: Try to subscribe to %s!", gazebo_ros_->info(), motor_power_topic.c_str());
00331
00332
00333 std::string odom_reset_topic = base_prefix + "/commands/reset_odometry";
00334 odom_reset_sub_ = gazebo_ros_->node()->subscribe(odom_reset_topic, 10, &GazeboRosKobuki::resetOdomCB, this);
00335 ROS_INFO("%s: Try to subscribe to %s!", gazebo_ros_->info(), odom_reset_topic.c_str());
00336
00337
00338 std::string cmd_vel = base_prefix + "/commands/velocity";
00339 cmd_vel_sub_ = gazebo_ros_->node()->subscribe(cmd_vel, 100, &GazeboRosKobuki::cmdVelCB, this);
00340 ROS_INFO("%s: Try to subscribe to %s!", gazebo_ros_->info(), motor_power_topic.c_str());
00341
00342
00343 std::string cliff_topic = base_prefix + "/events/cliff";
00344 cliff_event_pub_ = gazebo_ros_->node()->advertise<kobuki_msgs::CliffEvent>(cliff_topic, 1);
00345 ROS_INFO("%s: Advertise Cliff[%s]!", gazebo_ros_->info(), cliff_topic.c_str());
00346
00347
00348 std::string bumper_topic = base_prefix + "/events/bumper";
00349 bumper_event_pub_ = gazebo_ros_->node()->advertise<kobuki_msgs::BumperEvent>(bumper_topic, 1);
00350 ROS_INFO("%s: Advertise Bumper[%s]!", gazebo_ros_->info(), bumper_topic.c_str());
00351
00352
00353 std::string imu_topic = base_prefix + "/sensors/imu_data";
00354 imu_pub_ = gazebo_ros_->node()->advertise<sensor_msgs::Imu>(imu_topic, 1);
00355 ROS_INFO("%s: Advertise IMU[%s]!", gazebo_ros_->info(), imu_topic.c_str());
00356 }
00357 }