47   std::string baselink_frame = 
gazebo_ros_->resolveTF(
"base_link");
    51   #if GAZEBO_MAJOR_VERSION >= 9    71   std::string odom_frame = 
gazebo_ros_->resolveTF(
"odom");
    72   std::string base_frame = 
gazebo_ros_->resolveTF(
"base_footprint");
    74   odom_.header.frame_id = odom_frame;
    75   odom_.child_frame_id = base_frame;
   107   #if GAZEBO_MAJOR_VERSION >= 9   117   #if GAZEBO_MAJOR_VERSION >= 9   126   odom_.pose.pose.position.z = 0;
   130   odom_.pose.pose.orientation.x = qt.getX();
   131   odom_.pose.pose.orientation.y = qt.getY();
   132   odom_.pose.pose.orientation.z = qt.getZ();
   133   odom_.pose.pose.orientation.w = qt.
getW();
   135   odom_.pose.covariance[0]  = 0.1;
   136   odom_.pose.covariance[7]  = 0.1;
   137   odom_.pose.covariance[35] = 0.05;
   138   odom_.pose.covariance[14] = 1e6;
   139   odom_.pose.covariance[21] = 1e6;
   140   odom_.pose.covariance[28] = 1e6;
   143   odom_.twist.twist.linear.y = 0;
   144   odom_.twist.twist.linear.z = 0;
   145   odom_.twist.twist.angular.x = 0;
   146   odom_.twist.twist.angular.y = 0;
   154     odom_tf_.transform.translation.x = 
odom_.pose.pose.position.x;
   155     odom_tf_.transform.translation.y = 
odom_.pose.pose.position.y;
   156     odom_tf_.transform.translation.z = 
odom_.pose.pose.position.z;
   169   #if GAZEBO_MAJOR_VERSION >= 9   170     ignition::math::Quaterniond quat = 
imu_->Orientation();
   176     math::Quaternion quat = 
imu_->Orientation();
   184   imu_msg_.orientation_covariance[0] = 1e6;
   185   imu_msg_.orientation_covariance[4] = 1e6;
   186   imu_msg_.orientation_covariance[8] = 0.05;
   188   #if GAZEBO_MAJOR_VERSION >= 9   199   imu_msg_.angular_velocity_covariance[0] = 1e6;
   200   imu_msg_.angular_velocity_covariance[4] = 1e6;
   201   imu_msg_.angular_velocity_covariance[8] = 0.05;
   203   #if GAZEBO_MAJOR_VERSION >= 9   204     ignition::math::Vector3d lin_acc = 
imu_->LinearAcceleration();
   205     imu_msg_.linear_acceleration.x = lin_acc.X();
   206     imu_msg_.linear_acceleration.y = lin_acc.Y();
   207     imu_msg_.linear_acceleration.z = lin_acc.Z();
   209     math::Vector3 lin_acc = 
imu_->LinearAcceleration();
   210     imu_msg_.linear_acceleration.x = lin_acc.x;
   211     imu_msg_.linear_acceleration.y = lin_acc.y;
   212     imu_msg_.linear_acceleration.z = lin_acc.z;
   321   msgs::Contacts contacts;
   322   contacts = 
bumper_->Contacts();
   323   double robot_heading;
   324   #if GAZEBO_MAJOR_VERSION >= 9   325     ignition::math::Pose3d current_pose = 
model_->WorldPose();
   326     robot_heading = current_pose.Rot().Yaw();
   328     math::Pose current_pose = 
model_->GetWorldPose();
   329     robot_heading = current_pose.rot.GetYaw();
   333   for (
int i = 0; i < contacts.contact_size(); ++i)
   335     double rel_contact_pos;
   336     #if GAZEBO_MAJOR_VERSION >= 9   337       rel_contact_pos =  contacts.contact(i).position(0).z() - current_pose.Pos().Z();
   339       rel_contact_pos =  contacts.contact(i).position(0).z() - current_pose.pos.z;
   343     if ((rel_contact_pos >= 0.01)
   344         && (rel_contact_pos <= 0.13))
   348       double global_contact_angle = std::atan2(-contacts.contact(i).normal(0).y(), -contacts.contact(i).normal(0).x());
   349       double relative_contact_angle = global_contact_angle - robot_heading;
   351       if ((relative_contact_angle <= (M_PI/2)) && (relative_contact_angle > (M_PI/6)))
   355       else if ((relative_contact_angle <= (M_PI/6)) && (relative_contact_angle >= (-M_PI/6)))
   359       else if ((relative_contact_angle < (-M_PI/6)) && (relative_contact_angle >= (-M_PI/2)))
 bool cliff_detected_right_
Cliff flag for the right sensor. 
double odom_pose_[3]
Vector for pose. 
void publish(const boost::shared_ptr< M > &message) const 
void propagateVelocityCommands()
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 bumper_center_was_pressed_
Flag for center bumper's last state. 
bool cliff_detected_left_
Cliff flag for the left sensor. 
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. 
TFSIMD_FORCE_INLINE const tfScalar & getW() const 
bool bumper_right_was_pressed_
Flag for right bumper's last state. 
sensors::ImuSensorPtr imu_
Pointer to IMU sensor model. 
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's current state. 
double wheel_diam_
Diameter of the wheels. 
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. 
bool bumper_center_is_pressed_
Flag for left bumper's current state. 
void setEuler(const tfScalar &yaw, const tfScalar &pitch, const tfScalar &roll)
#define ROS_WARN_STREAM_THROTTLE(rate, args)
ros::Publisher odom_pub_
ROS publisher for odometry messages. 
double cmd_vel_timeout_
Time out for velocity commands in seconds. 
double odom_vel_[3]
Vector for velocity. 
bool cliff_detected_center_
Cliff flag for the center sensor. 
bool bumper_left_was_pressed_
Flag for left bumper's last state. 
geometry_msgs::TransformStamped odom_tf_
TF transform for the odom frame. 
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. 
ros::Publisher cliff_event_pub_
ROS publisher for cliff detection events. 
bool bumper_right_is_pressed_
Flag for left bumper'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.