53   if (
sdf_->HasElement(
"left_wheel_joint_name"))
    60                      << 
" Did you specify the correct joint name?" << 
" [" << 
node_name_ <<
"]");
    63   if (
sdf_->HasElement(
"right_wheel_joint_name"))
    70                      << 
" Did you specify the correct joint name?" << 
" [" << 
node_name_ <<
"]");
    98   if (
sdf_->HasElement(
"publish_tf"))
   113     ROS_INFO_STREAM(
"Couldn't find the 'publish tf' parameter in the model description."   114                      << 
" Won't publish tf." << 
" [" << 
node_name_ <<
"]");
   120   if (
sdf_->HasElement(
"wheel_separation"))
   126     ROS_ERROR_STREAM(
"Couldn't find the wheel separation parameter in the model description!"   127                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   130   if (
sdf_->HasElement(
"wheel_diameter"))
   136     ROS_ERROR_STREAM(
"Couldn't find the wheel diameter parameter in the model description!"   137                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   140   if (
sdf_->HasElement(
"torque"))
   142     torque_ = 
sdf_->GetElement(
"torque")->Get<
double>();
   146     ROS_ERROR_STREAM(
"Couldn't find the torque parameter in the model description!"   147                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   165   if (
sdf_->HasElement(
"velocity_command_timeout"))
   171     ROS_ERROR_STREAM(
"Couldn't find the wheel separation parameter in the model description!"   172                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   175   #if GAZEBO_MAJOR_VERSION >= 9   188   std::string cliff_sensor_left_name, cliff_sensor_center_name, cliff_sensor_right_name;
   189   if (
sdf_->HasElement(
"cliff_sensor_left_name"))
   191     cliff_sensor_left_name = 
sdf_->GetElement(
"cliff_sensor_left_name")->Get<std::string>();
   195     ROS_ERROR_STREAM(
"Couldn't find the name of left cliff sensor in the model description!"   196                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   199   if (
sdf_->HasElement(
"cliff_sensor_center_name"))
   201     cliff_sensor_center_name = 
sdf_->GetElement(
"cliff_sensor_center_name")->Get<std::string>();
   205     ROS_ERROR_STREAM(
"Couldn't find the name of frontal cliff sensor in the model description!"   206                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   209   if (
sdf_->HasElement(
"cliff_sensor_right_name"))
   211     cliff_sensor_right_name = 
sdf_->GetElement(
"cliff_sensor_right_name")->Get<std::string>();
   215     ROS_ERROR_STREAM(
"Couldn't find the name of right cliff sensor in the model description!"   216                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   220                        sensors::SensorManager::Instance()->GetSensor(cliff_sensor_left_name));
   222                         sensors::SensorManager::Instance()->GetSensor(cliff_sensor_center_name));
   224                         sensors::SensorManager::Instance()->GetSensor(cliff_sensor_right_name));
   230   if (!cliff_sensor_center_)
   235   if (!cliff_sensor_right_)
   240   if (
sdf_->HasElement(
"cliff_detection_threshold"))
   246     ROS_ERROR_STREAM(
"Couldn't find the cliff detection threshold parameter in the model description!"   247                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   251   cliff_sensor_center_->SetActive(
true);
   252   cliff_sensor_right_->SetActive(
true);
   263   std::string bumper_name;
   264   if (
sdf_->HasElement(
"bumper_name"))
   266     bumper_name = 
sdf_->GetElement(
"bumper_name")->Get<std::string>();
   270     ROS_ERROR_STREAM(
"Couldn't find the name of bumper sensor in the model description!"   271                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   274   bumper_ = std::dynamic_pointer_cast<sensors::ContactSensor>(
   275             sensors::SensorManager::Instance()->GetSensor(bumper_name));
   290   std::string imu_name;
   291   if (
sdf_->HasElement(
"imu_name"))
   293   imu_name = 
sdf_->GetElement(
"imu_name")->Get<std::string>();
   297     ROS_ERROR_STREAM(
"Couldn't find the name of IMU sensor in the model description!"   298                      << 
" Did you specify it?" << 
" [" << 
node_name_ <<
"]");
   301   #if GAZEBO_MAJOR_VERSION >= 9   302     imu_ = std::dynamic_pointer_cast<sensors::ImuSensor>(
   303             sensors::get_sensor(
world_->Name()+
"::"+
node_name_+
"::base_footprint::"+imu_name));
   305     imu_ = std::dynamic_pointer_cast<sensors::ImuSensor>(
   306             sensors::get_sensor(
world_->GetName()+
"::"+
node_name_+
"::base_footprint::"+imu_name));
   314   imu_->SetActive(
true);
   320   std::string base_prefix;
   321   gazebo_ros_->node()->param(
"base_prefix", base_prefix, std::string(
"mobile_base"));
   326   std::string joint_states_topic = 
"joint_states";
   328   ROS_INFO(
"%s: Advertise joint_states[%s]!", 
gazebo_ros_->info(), joint_states_topic.c_str());
   331   std::string odom_topic = 
"odom";
   338   std::string motor_power_topic = base_prefix + 
"/commands/motor_power";
   343   std::string odom_reset_topic = base_prefix + 
"/commands/reset_odometry";
   348   std::string cmd_vel_topic = base_prefix + 
"/commands/velocity";
   353   std::string cliff_topic = base_prefix + 
"/events/cliff";
   358   std::string bumper_topic = base_prefix + 
"/events/bumper";
   363   std::string imu_topic = base_prefix + 
"/sensors/imu_data";
 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. 
ros::Publisher imu_pub_
ROS publisher for IMU data. 
sensors::RaySensorPtr cliff_sensor_center_
Pointer to frontal cliff sensor. 
bool prepareWheelAndTorque()
ros::Subscriber cmd_vel_sub_
ROS subscriber for velocity commands. 
sensors::ContactSensorPtr bumper_
Pointer to bumper sensor simulating Kobuki's left, centre and right bumper sensors. 
physics::JointPtr joints_[2]
Pointers to Gazebo's joints. 
bool prepareCliffSensor()
sensors::ImuSensorPtr imu_
Pointer to IMU sensor model. 
ros::Subscriber odom_reset_sub_
ROS subscriber for reseting the odometry 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. 
double wheel_diam_
Diameter of the wheels. 
bool prepareVelocityCommand()
void setupRosApi(std::string &model_name)
bool motors_enabled_
Flag indicating if the motors are turned on or not. 
ros::Publisher bumper_event_pub_
ROS publisher for bumper events. 
physics::ModelPtr model_
pointer to the model 
void motorPowerCB(const kobuki_msgs::MotorPowerPtr &msg)
Callback for incoming velocity commands. 
ros::Publisher odom_pub_
ROS publisher for odometry messages. 
std::string right_wheel_joint_name_
Right wheel'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. 
#define ROS_INFO_STREAM(args)
std::string left_wheel_joint_name_
Left wheel's joint name. 
void cmdVelCB(const geometry_msgs::TwistConstPtr &msg)
Callback for incoming velocity commands. 
#define ROS_ERROR_STREAM(args)
std::string node_name_
node name 
sensors::RaySensorPtr cliff_sensor_left_
Pointer to left cliff sensor. 
physics::WorldPtr world_
pointer to simulated world 
ros::Publisher cliff_event_pub_
ROS publisher for cliff detection events. 
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. 
ros::Subscriber motor_power_sub_
ROS subscriber for motor power commands.