Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix #612 for Gazebo9 #688

Merged
merged 2 commits into from
Mar 17, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -384,8 +384,13 @@ void GazeboRosJointPoseTrajectory::UpdateStates()
// this is not the most efficient way to set things
if (this->joints_[i])
{
#if GAZEBO_MAJOR_VERSION >= 9
this->joints_[i]->SetPosition(0,
this->points_[this->trajectory_index].positions[i], true);
#else
this->joints_[i]->SetPosition(0,
this->points_[this->trajectory_index].positions[i]);
#endif
}
}

Expand Down
5 changes: 5 additions & 0 deletions gazebo_plugins/src/gazebo_ros_joint_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -386,8 +386,13 @@ void GazeboRosJointTrajectory::UpdateStates()
// this is not the most efficient way to set things
if (this->joints_[i])
{
#if GAZEBO_MAJOR_VERSION >= 9
this->joints_[i]->SetPosition(0,
this->points_[this->trajectory_index].positions[i], true);
#else
this->joints_[i]->SetPosition(0,
this->points_[this->trajectory_index].positions[i]);
#endif
}
}

Expand Down
4 changes: 4 additions & 0 deletions gazebo_plugins/src/gazebo_ros_tricycle_drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -317,7 +317,11 @@ void GazeboRosTricycleDrive::motorController ( double target_speed, double targe
{
applied_angle = target_angle;
}
#if GAZEBO_MAJOR_VERSION >= 9
joint_steering_->SetPosition(0, applied_angle, true);
#else
joint_steering_->SetPosition(0, applied_angle);
#endif
}
//ROS_INFO_NAMED("tricycle_drive", "target: [%3.2f, %3.2f], current: [%3.2f, %3.2f], applied: [%3.2f, %3.2f/%3.2f] ",
// target_speed, target_angle, current_speed, current_angle, applied_speed, applied_angle, applied_steering_speed );
Expand Down
6 changes: 3 additions & 3 deletions gazebo_ros_control/src/default_robot_hw_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -306,10 +306,10 @@ void DefaultRobotHWSim::writeSim(ros::Time time, ros::Duration period)
break;

case POSITION:
#if GAZEBO_MAJOR_VERSION >= 4
sim_joints_[j]->SetPosition(0, joint_position_command_[j]);
#if GAZEBO_MAJOR_VERSION >= 9
sim_joints_[j]->SetPosition(0, joint_position_command_[j], true);
#else
sim_joints_[j]->SetAngle(0, joint_position_command_[j]);
sim_joints_[j]->SetPosition(0, joint_position_command_[j]);
#endif
break;

Expand Down