Skip to content

Commit

Permalink
Add warnings when the user is affected by ros-simulation#612
Browse files Browse the repository at this point in the history
  • Loading branch information
mintar committed Mar 20, 2018
1 parent 3164e4c commit 1d6616e
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 0 deletions.
4 changes: 4 additions & 0 deletions gazebo_plugins/src/gazebo_ros_joint_pose_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -388,6 +388,10 @@ void GazeboRosJointPoseTrajectory::UpdateStates()
this->joints_[i]->SetPosition(0,
this->points_[this->trajectory_index].positions[i], true);
#else
ROS_WARN_ONCE("The joint_pose_trajectory plugin is using the Joint::SetPosition method without preserving the link velocity.");
ROS_WARN_ONCE("As a result, gravity will not be simulated correctly for your model.");
ROS_WARN_ONCE("Please upgrade to Gazebo 9.");
ROS_WARN_ONCE("For details, see https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612");
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_joint_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -390,6 +390,10 @@ void GazeboRosJointTrajectory::UpdateStates()
this->joints_[i]->SetPosition(0,
this->points_[this->trajectory_index].positions[i], true);
#else
ROS_WARN_ONCE("The joint_trajectory plugin is using the Joint::SetPosition method without preserving the link velocity.");
ROS_WARN_ONCE("As a result, gravity will not be simulated correctly for your model.");
ROS_WARN_ONCE("Please upgrade to Gazebo 9.");
ROS_WARN_ONCE("For details, see https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612");
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 @@ -320,6 +320,10 @@ void GazeboRosTricycleDrive::motorController ( double target_speed, double targe
#if GAZEBO_MAJOR_VERSION >= 9
joint_steering_->SetPosition(0, applied_angle, true);
#else
ROS_WARN_ONCE("The tricycle_drive plugin is using the Joint::SetPosition method without preserving the link velocity.");
ROS_WARN_ONCE("As a result, gravity will not be simulated correctly for your model.");
ROS_WARN_ONCE("Please upgrade to Gazebo 9.");
ROS_WARN_ONCE("For details, see https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612");
joint_steering_->SetPosition(0, applied_angle);
#endif
}
Expand Down
4 changes: 4 additions & 0 deletions gazebo_ros_control/src/default_robot_hw_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -309,6 +309,10 @@ void DefaultRobotHWSim::writeSim(ros::Time time, ros::Duration period)
#if GAZEBO_MAJOR_VERSION >= 9
sim_joints_[j]->SetPosition(0, joint_position_command_[j], true);
#else
ROS_WARN_ONCE("The default_robot_hw_sim plugin is using the Joint::SetPosition method without preserving the link velocity.");
ROS_WARN_ONCE("As a result, gravity will not be simulated correctly for your model.");
ROS_WARN_ONCE("Please set gazebo_pid parameters, switch to the VelocityJointInterface or EffortJointInterface, or upgrade to Gazebo 9.");
ROS_WARN_ONCE("For details, see https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612");
sim_joints_[j]->SetPosition(0, joint_position_command_[j]);
#endif
break;
Expand Down

0 comments on commit 1d6616e

Please sign in to comment.