Skip to content

Commit

Permalink
fixes for gazebo9 (melodic)
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Jun 5, 2018
1 parent 545769a commit 146ae27
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
10 changes: 5 additions & 5 deletions fetch_gazebo/include/fetch_gazebo/joint_handle.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,9 +128,9 @@ class JointHandle : public robot_controllers::JointHandle
{
if (continuous_)
{
return angles::normalize_angle(joint_->GetAngle(0).Radian());
return angles::normalize_angle(joint_->Position(0));
}
return joint_->GetAngle(0).Radian();
return joint_->Position(0);
}

/** @brief Get the velocity of the joint in rad/sec or meters/sec. */
Expand All @@ -154,13 +154,13 @@ class JointHandle : public robot_controllers::JointHandle
/** @brief Get the minimum valid position command. */
virtual double getPositionMin()
{
return joint_->GetLowerLimit(0).Radian();
return joint_->LowerLimit(0);
}

/** @brief Get the maximum valid position command. */
virtual double getPositionMax()
{
return joint_->GetUpperLimit(0).Radian();
return joint_->UpperLimit(0);
}

/** @brief Get the maximum velocity command. */
Expand Down Expand Up @@ -271,4 +271,4 @@ typedef boost::shared_ptr<JointHandle> JointHandlePtr;

} // namespace gazebo

#endif // FETCH_GAZEBO_JOINT_HANDLE_H
#endif // FETCH_GAZEBO_JOINT_HANDLE_H
6 changes: 3 additions & 3 deletions fetch_gazebo/src/plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ void FetchGazeboPlugin::Load(
void FetchGazeboPlugin::Init()
{
// Init time stuff
prevUpdateTime = model_->GetWorld()->GetSimTime();
prevUpdateTime = model_->GetWorld()->SimTime();
last_publish_ = ros::Time(prevUpdateTime.Double());
urdf::Model urdfmodel;
if (!urdfmodel.initParam("robot_description"))
Expand All @@ -107,7 +107,7 @@ void FetchGazeboPlugin::Init()
for (physics::Joint_V::iterator it = joints.begin(); it != joints.end(); ++it)
{
//get effort limit and continuous state from URDF
boost::shared_ptr<const urdf::Joint> urdf_joint = urdfmodel.getJoint((*it)->GetName());
std::shared_ptr<const urdf::Joint> urdf_joint = urdfmodel.getJoint((*it)->GetName());

JointHandlePtr handle(new JointHandle(*it,
urdf_joint->limits->velocity,
Expand Down Expand Up @@ -135,7 +135,7 @@ void FetchGazeboPlugin::OnUpdate(
return;

// Get time and timestep for controllers
common::Time currTime = model_->GetWorld()->GetSimTime();
common::Time currTime = model_->GetWorld()->SimTime();
common::Time stepTime = currTime - prevUpdateTime;
prevUpdateTime = currTime;
double dt = stepTime.Double();
Expand Down

0 comments on commit 146ae27

Please sign in to comment.