Skip to content

Commit

Permalink
fixes for compile with gazebo 9 (#143)
Browse files Browse the repository at this point in the history
  • Loading branch information
davefeilseifer authored and v4hn committed Apr 5, 2019
1 parent e4aa25d commit 779da3a
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
16 changes: 8 additions & 8 deletions pr2_gazebo_plugins/src/gazebo_ros_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,8 +119,8 @@ void GazeboRosControllerManager::Load(physics::ModelPtr _parent, sdf::ElementPtr

if (getenv("CHECK_SPEEDUP"))
{
wall_start_ = this->world->GetRealTime().Double();
sim_start_ = this->world->GetSimTime().Double();
wall_start_ = this->world->RealTime().Double();
sim_start_ = this->world->SimTime().Double();
}

// check update rate against world physics update rate
Expand Down Expand Up @@ -159,7 +159,7 @@ void GazeboRosControllerManager::Load(physics::ModelPtr _parent, sdf::ElementPtr

// load a controller manager
this->cm_ = new pr2_controller_manager::ControllerManager(&hw_,*this->rosnode_);
this->hw_.current_time_ = ros::Time(this->world->GetSimTime().Double());
this->hw_.current_time_ = ros::Time(this->world->SimTime().Double());
if (this->hw_.current_time_ < ros::Time(0.001)) this->hw_.current_time_ == ros::Time(0.001); // hardcoded to minimum of 1ms on start up

this->rosnode_->param("gazebo/start_robot_calibrated",this->fake_calibration_,true);
Expand Down Expand Up @@ -209,8 +209,8 @@ void GazeboRosControllerManager::UpdateChild()

if (getenv("CHECK_SPEEDUP"))
{
double wall_elapsed = this->world->GetRealTime().Double() - wall_start_;
double sim_elapsed = this->world->GetSimTime().Double() - sim_start_;
double wall_elapsed = this->world->RealTime().Double() - wall_start_;
double sim_elapsed = this->world->SimTime().Double() - sim_start_;
std::cout << " real time: " << wall_elapsed
<< " sim time: " << sim_elapsed
<< " speed up: " << sim_elapsed / wall_elapsed
Expand All @@ -235,7 +235,7 @@ void GazeboRosControllerManager::UpdateChild()
{
gazebo::physics::JointPtr hj = this->joints_[i];
this->fake_state_->joint_states_[i].position_ = this->fake_state_->joint_states_[i].position_ +
angles::shortest_angular_distance(this->fake_state_->joint_states_[i].position_,hj->GetAngle(0).Radian());
angles::shortest_angular_distance(this->fake_state_->joint_states_[i].position_,hj->Position(0));
this->fake_state_->joint_states_[i].velocity_ = hj->GetVelocity(0);
//if (this->joints_[i]->GetName() == "torso_lift_motor_screw_joint")
// ROS_WARN("joint[%s] [%f]",this->joints_[i]->GetName().c_str(), this->fake_state_->joint_states_[i].position_);
Expand All @@ -244,7 +244,7 @@ void GazeboRosControllerManager::UpdateChild()
{
gazebo::physics::JointPtr sj = this->joints_[i];
{
this->fake_state_->joint_states_[i].position_ = sj->GetAngle(0).Radian();
this->fake_state_->joint_states_[i].position_ = sj->Position(0);
this->fake_state_->joint_states_[i].velocity_ = sj->GetVelocity(0);
}
//ROS_ERROR("joint[%s] is a slider [%f]",this->joints_[i]->GetName().c_str(),sj->GetAngle(0).Radian());
Expand All @@ -271,7 +271,7 @@ void GazeboRosControllerManager::UpdateChild()
//--------------------------------------------------
// Runs Mechanism Control
//--------------------------------------------------
this->hw_.current_time_ = ros::Time(this->world->GetSimTime().Double());
this->hw_.current_time_ = ros::Time(this->world->SimTime().Double());
try
{
if (this->cm_->state_ != NULL) // could be NULL if ReadPr2Xml is unsuccessful
Expand Down
4 changes: 2 additions & 2 deletions pr2_gazebo_plugins/src/gazebo_ros_power_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ void GazeboRosPowerMonitor::LoadThread()
charge_ = this->full_capacity_;
charge_rate_ = this->discharge_rate_;
voltage_ = this->discharge_voltage_;
last_time_ = this->world_->GetSimTime().Double();
last_time_ = this->world_->SimTime().Double();

// Listen to the update event. This event is broadcast every
// simulation iteration.
Expand Down Expand Up @@ -185,7 +185,7 @@ void GazeboRosPowerMonitor::QueueThread()
void GazeboRosPowerMonitor::UpdateChild()
{
// Update time
double curr_time_ = this->world_->GetSimTime().Double();
double curr_time_ = this->world_->SimTime().Double();
double dt = curr_time_ - last_time_;

if (dt < this->power_state_rate_)
Expand Down

0 comments on commit 779da3a

Please sign in to comment.