commit b5303e692bb5dd2e4f4fc7932c7ec2c7e0b2e907 Author: Steven Peters Date: Tue Apr 14 18:10:36 2015 -0700 Use Joint::SetParam for joint velocity motors Before gazebo5, Joint::SetVelocity and SetMaxForce were used to set joint velocity motors. The API has changed in gazebo5, to use Joint::SetParam instead. The functionality is still available through the SetParam API. cherry-picked from indigo-devel Add ifdefs to fix build with gazebo2 It was broken by #315. Fixes #321. diff --git a/gazebo_ros_control/src/default_robot_hw_sim.cpp b/gazebo_ros_control/src/default_robot_hw_sim.cpp index 249c8d3..1d9418d 100644 --- a/gazebo_ros_control/src/default_robot_hw_sim.cpp +++ b/gazebo_ros_control/src/default_robot_hw_sim.cpp @@ -199,7 +199,7 @@ bool DefaultRobotHWSim::initSim( if (joint_control_methods_[j] != EFFORT) { // Initialize the PID controller. If no PID gain values are found, use joint->SetAngle() or - // joint->SetVelocity() to control the joint. + // joint->SetParam("vel") to control the joint. const ros::NodeHandle nh(model_nh, "/gazebo_ros_control/pid_gains/" + joint_names_[j]); if (pid_controllers_[j].init(nh, true)) @@ -216,10 +216,14 @@ bool DefaultRobotHWSim::initSim( } else { - // joint->SetMaxForce() must be called if joint->SetAngle() or joint->SetVelocity() are - // going to be called. joint->SetMaxForce() must *not* be called if joint->SetForce() is + // joint->SetParam("fmax") must be called if joint->SetAngle() or joint->SetParam("vel") are + // going to be called. joint->SetParam("fmax") must *not* be called if joint->SetForce() is // going to be called. +#if GAZEBO_MAJOR_VERSION > 2 + joint->SetParam("fmax", 0, joint_effort_limits_[j]); +#else joint->SetMaxForce(0, joint_effort_limits_[j]); +#endif } } } @@ -327,7 +331,11 @@ void DefaultRobotHWSim::writeSim(ros::Time time, ros::Duration period) break; case VELOCITY: +#if GAZEBO_MAJOR_VERSION > 2 + sim_joints_[j]->SetParam("vel", 0, e_stop_active_ ? 0 : joint_velocity_command_[j]); +#else sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_command_[j]); +#endif break; case VELOCITY_PID: