Skip to content

Commit

Permalink
Fix gazebo8 warnings part 7: retry ros-simulation#642 on lunar (ros-s…
Browse files Browse the repository at this point in the history
…imulation#660)

ifdef's for Joint::GetAngle and some cleanup (ros-simulation#642)

* fix major version check >= 8, instead of > 8

* gazebo_ros_bumper: use new API in commented code

* gazebo_ros_api_plugin: world pose in local vars

* worldLinearVel as local var in hand of god plugin

* gazebo8+: Joint::GetAngle -> Joint::Position
  • Loading branch information
scpeters authored and j-rivero committed Dec 27, 2017
1 parent 7564810 commit 7d5eb73
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 8 deletions.
6 changes: 3 additions & 3 deletions gazebo_plugins/src/gazebo_ros_bumper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,9 +183,9 @@ void GazeboRosBumper::OnContact()
/*
if (myFrame)
{
frame_pose = myFrame->GetWorldPose(); //-this->myBody->GetCoMPose();
frame_pos = frame_pose.pos;
frame_rot = frame_pose.rot;
frame_pose = myFrame->WorldPose(); //-this->myBody->GetCoMPose();
frame_pos = frame_pose.Pos();
frame_rot = frame_pose.Rot();
}
else
*/
Expand Down
8 changes: 6 additions & 2 deletions gazebo_plugins/src/gazebo_ros_diff_drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,9 +203,13 @@ void GazeboRosDiffDrive::publishWheelJointState()

for ( int i = 0; i < 2; i++ ) {
physics::JointPtr joint = joints_[i];
ignition::math::Angle angle = joint->GetAngle ( 0 ).Ign();
#if GAZEBO_MAJOR_VERSION >= 8
double position = joint->Position ( 0 );
#else
double position = joint->GetAngle ( 0 ).Radian();
#endif
joint_state_.name[i] = joint->GetName();
joint_state_.position[i] = angle.Radian () ;
joint_state_.position[i] = position;
}
joint_state_publisher_.publish ( joint_state_ );
}
Expand Down
4 changes: 3 additions & 1 deletion gazebo_plugins/src/gazebo_ros_hand_of_god.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,9 +161,11 @@ namespace gazebo
// Relative transform from actual to desired pose
#if GAZEBO_MAJOR_VERSION >= 8
ignition::math::Pose3d world_pose = floating_link_->DirtyPose();
ignition::math::Vector3d worldLinearVel = floating_link_->WorldLinearVel();
ignition::math::Vector3d relativeAngularVel = floating_link_->RelativeAngularVel();
#else
ignition::math::Pose3d world_pose = floating_link_->GetDirtyPose().Ign();
ignition::math::Vector3d worldLinearVel = floating_link_->GetWorldLinearVel().Ign();
ignition::math::Vector3d relativeAngularVel = floating_link_->GetRelativeAngularVel().Ign();
#endif
ignition::math::Vector3d err_pos = hog_desired.Pos() - world_pose.Pos();
Expand All @@ -173,7 +175,7 @@ namespace gazebo
ignition::math::Quaterniond not_a_quaternion = err_rot.Log();

floating_link_->AddForce(
kl_ * err_pos - cl_ * floating_link_->GetWorldLinearVel().Ign());
kl_ * err_pos - cl_ * worldLinearVel);

floating_link_->AddRelativeTorque(
ka_ * ignition::math::Vector3d(not_a_quaternion.X(), not_a_quaternion.Y(), not_a_quaternion.Z())
Expand Down
8 changes: 6 additions & 2 deletions gazebo_plugins/src/gazebo_ros_joint_state_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,9 +124,13 @@ void GazeboRosJointStatePublisher::publishJointStates() {

for ( int i = 0; i < joints_.size(); i++ ) {
physics::JointPtr joint = joints_[i];
ignition::math::Angle angle = joint->GetAngle ( 0 ).Ign();
#if GAZEBO_MAJOR_VERSION >= 8
double position = joint->Position ( 0 );
#else
double position = joint->GetAngle ( 0 ).Radian();
#endif
joint_state_.name[i] = joint->GetName();
joint_state_.position[i] = angle.Radian () ;
joint_state_.position[i] = position;
}
joint_state_publisher_.publish ( joint_state_ );
}
8 changes: 8 additions & 0 deletions gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,11 @@ void GazeboRosTricycleDrive::publishWheelJointState()
joint_state_.effort.resize ( joints.size() );
for ( std::size_t i = 0; i < joints.size(); i++ ) {
joint_state_.name[i] = joints[i]->GetName();
#if GAZEBO_MAJOR_VERSION >= 8
joint_state_.position[i] = joints[i]->Position ( 0 );
#else
joint_state_.position[i] = joints[i]->GetAngle ( 0 ).Radian();
#endif
joint_state_.velocity[i] = joints[i]->GetVelocity ( 0 );
joint_state_.effort[i] = joints[i]->GetForce ( 0 );
}
Expand Down Expand Up @@ -250,7 +254,11 @@ void GazeboRosTricycleDrive::motorController ( double target_speed, double targe
}
joint_wheel_actuated_->SetParam ( "vel", 0, applied_speed );

#if GAZEBO_MAJOR_VERSION >= 8
double current_angle = joint_steering_->Position ( 0 );
#else
double current_angle = joint_steering_->GetAngle ( 0 ).Radian();
#endif

// truncate target angle
if (target_angle > +M_PI / 2.0)
Expand Down

0 comments on commit 7d5eb73

Please sign in to comment.