47 #ifdef ENABLE_PROFILER 
   48 #include <ignition/common/Profiler.hh> 
   50 #include <ignition/math/Pose3.hh> 
   51 #include <ignition/math/Vector3.hh> 
   57 #include <geometry_msgs/Twist.h> 
   58 #include <nav_msgs/GetMap.h> 
   59 #include <nav_msgs/Odometry.h> 
   60 #include <boost/bind.hpp> 
   61 #include <boost/thread/mutex.hpp> 
  110     std::map<std::string, OdomSource> odomOptions;
 
  111     odomOptions[
"encoder"] = 
ENCODER;
 
  112     odomOptions[
"world"] = 
WORLD;
 
  122 #if GAZEBO_MAJOR_VERSION >= 8 
  142         ros::SubscribeOptions::create<geometry_msgs::Twist> ( 
command_topic_, 1,
 
  162     std::vector<physics::JointPtr> joints;
 
  174     for ( std::size_t i = 0; i < joints.size(); i++ ) {
 
  176 #if GAZEBO_MAJOR_VERSION >= 8 
  179         joint_state_.position[i] = joints[i]->GetAngle ( 0 ).Radian();
 
  181         joint_state_.velocity[i] = joints[i]->GetVelocity ( 0 );
 
  190     std::vector<physics::JointPtr> joints;
 
  195     for ( std::size_t i = 0; i < joints.size(); i++ ) {
 
  196         std::string frame = 
gazebo_ros_->resolveTF ( joints[i]->GetName() );
 
  197         std::string parent_frame = 
gazebo_ros_->resolveTF ( joints[i]->GetParent()->GetName() );
 
  199 #if GAZEBO_MAJOR_VERSION >= 8 
  200         ignition::math::Pose3d pose = joints[i]->GetChild()->RelativePose();
 
  202         ignition::math::Pose3d pose = joints[i]->GetChild()->GetRelativePose().Ign();
 
  205         tf::Quaternion qt ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
 
  206         tf::Vector3 vt ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
 
  216 #ifdef ENABLE_PROFILER 
  217   IGN_PROFILE(
"GazeboRosTricycleDrive::UpdateChild");
 
  221 #ifdef ENABLE_PROFILER 
  222       IGN_PROFILE_BEGIN(
"UpdateOdometryEncoder");
 
  225 #ifdef ENABLE_PROFILER 
  229 #if GAZEBO_MAJOR_VERSION >= 8 
  230     common::Time current_time = 
parent->GetWorld()->SimTime();
 
  232     common::Time current_time = 
parent->GetWorld()->GetSimTime();
 
  236 #ifdef ENABLE_PROFILER 
  237         IGN_PROFILE_BEGIN(
"publishOdometry");
 
  240 #ifdef ENABLE_PROFILER 
  245 #ifdef ENABLE_PROFILER 
  246           IGN_PROFILE_BEGIN(
"publishWheelTF");
 
  249 #ifdef ENABLE_PROFILER 
  255 #ifdef ENABLE_PROFILER 
  256           IGN_PROFILE_BEGIN(
"publishWheelJointState");
 
  259 #ifdef ENABLE_PROFILER 
  265         double target_steering_angle = 
cmd_.
angle;
 
  267         motorController ( target_wheel_roation_speed, target_steering_angle, seconds_since_last_update );
 
  278     double applied_speed = target_speed;
 
  279     double applied_angle = target_angle;
 
  284       double diff_speed = current_speed - target_speed;
 
  287         applied_speed = current_speed;
 
  303 #if GAZEBO_MAJOR_VERSION >= 8 
  310     if (target_angle > +M_PI / 2.0)
 
  312       target_angle =  +M_PI / 2.0;
 
  314     else if (target_angle < -M_PI / 2.0)
 
  316       target_angle =  -M_PI / 2.0;
 
  321     double diff_angle = current_angle - target_angle;
 
  324       double applied_steering_speed = 0;
 
  327         applied_steering_speed = 0;
 
  328       } 
else if ( diff_angle < target_speed ) {
 
  356         applied_angle = target_angle;
 
  358 #if GAZEBO_MAJOR_VERSION >= 9 
  380     boost::mutex::scoped_lock scoped_lock ( 
lock );
 
  387     static const double timeout = 0.01;
 
  398 #if GAZEBO_MAJOR_VERSION >= 8 
  399     common::Time current_time = 
parent->GetWorld()->SimTime();
 
  401     common::Time current_time = 
parent->GetWorld()->GetSimTime();
 
  403     double seconds_since_last_update = ( current_time - 
last_odom_update_ ).Double();
 
  411     double theta = ( sl - sr ) /b;
 
  414     double dx = ( sl + sr ) /2.0 * cos ( 
pose_encoder_.theta + ( sl - sr ) / ( 2.0*b ) );
 
  415     double dy = ( sl + sr ) /2.0 * sin ( 
pose_encoder_.theta + ( sl - sr ) / ( 2.0*b ) );
 
  416     double dtheta = ( sl - sr ) /b;
 
  422     double w = dtheta/seconds_since_last_update;
 
  423     double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
 
  430     odom_.pose.pose.position.x = vt.x();
 
  431     odom_.pose.pose.position.y = vt.y();
 
  432     odom_.pose.pose.position.z = vt.z();
 
  434     odom_.pose.pose.orientation.x = qt.x();
 
  435     odom_.pose.pose.orientation.y = qt.y();
 
  436     odom_.pose.pose.orientation.z = qt.z();
 
  437     odom_.pose.pose.orientation.w = qt.w();
 
  439     odom_.twist.twist.angular.z = w;
 
  440     odom_.twist.twist.linear.x = dx/seconds_since_last_update;
 
  441     odom_.twist.twist.linear.y = dy/seconds_since_last_update;
 
  457         vt = tf::Vector3 ( 
odom_.pose.pose.position.x, 
odom_.pose.pose.position.y, 
odom_.pose.pose.position.z );
 
  462 #if GAZEBO_MAJOR_VERSION >= 8 
  463         ignition::math::Pose3d pose = 
parent->WorldPose();
 
  465         ignition::math::Pose3d pose = 
parent->GetWorldPose().Ign();
 
  467         qt = 
tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
 
  468         vt = tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
 
  470         odom_.pose.pose.position.x = vt.x();
 
  471         odom_.pose.pose.position.y = vt.y();
 
  472         odom_.pose.pose.position.z = vt.z();
 
  474         odom_.pose.pose.orientation.x = qt.x();
 
  475         odom_.pose.pose.orientation.y = qt.y();
 
  476         odom_.pose.pose.orientation.z = qt.z();
 
  477         odom_.pose.pose.orientation.w = qt.w();
 
  480         ignition::math::Vector3d linear;
 
  481 #if GAZEBO_MAJOR_VERSION >= 8 
  482         linear = 
parent->WorldLinearVel();
 
  483         odom_.twist.twist.angular.z = 
parent->WorldAngularVel().Z();
 
  485         linear = 
parent->GetWorldLinearVel().Ign();
 
  486         odom_.twist.twist.angular.z = 
parent->GetWorldAngularVel().Ign().Z();
 
  490         float yaw = pose.Rot().Yaw();
 
  491         odom_.twist.twist.linear.x = cosf ( yaw ) * linear.X() + sinf ( yaw ) * linear.Y();
 
  492         odom_.twist.twist.linear.y = cosf ( yaw ) * linear.Y() - sinf ( yaw ) * linear.X();
 
  498                                odom_frame, base_footprint_frame ) );
 
  502     odom_.pose.covariance[0] = 0.00001;
 
  503     odom_.pose.covariance[7] = 0.00001;
 
  504     odom_.pose.covariance[14] = 1000000000000.0;
 
  505     odom_.pose.covariance[21] = 1000000000000.0;
 
  506     odom_.pose.covariance[28] = 1000000000000.0;
 
  507     odom_.pose.covariance[35] = 0.001;
 
  511     odom_.header.stamp = current_time;
 
  512     odom_.header.frame_id = odom_frame;
 
  513     odom_.child_frame_id = base_footprint_frame;