Skip to content

Commit

Permalink
query physics engine type
Browse files Browse the repository at this point in the history
  • Loading branch information
fmessmer committed Aug 5, 2019
1 parent d68adfb commit 72fbd71
Showing 1 changed file with 13 additions and 0 deletions.
13 changes: 13 additions & 0 deletions cob_gazebo_ros_control/src/hwi_switch_robot_hw_sim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -231,6 +231,19 @@ bool HWISwitchRobotHWSim::initSim(
sim_joints_.push_back(joint);


// get physics engine type
#if GAZEBO_MAJOR_VERSION >= 8
gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->Physics();
#else
gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->GetPhysicsEngine();
#endif
physics_type_ = physics->GetType();
if (physics_type_.empty())
{
ROS_WARN_STREAM_NAMED("default_robot_hw_sim", "No physics type found.");
}


// ToDo: Can a joint (gazebo::physics::JointPtr) be used for EFFORT if joint->SetMaxForce has been called before?
if (joint_control_methods_[index] == VELOCITY || joint_control_methods_[index] == POSITION)
{
Expand Down

0 comments on commit 72fbd71

Please sign in to comment.