23 #include <gazebo/common/Events.hh>
24 #include <gazebo/gazebo_config.h>
33 physics_reconfigure_initialized_(false),
34 world_created_(false),
36 plugin_loaded_(false),
37 pub_link_states_connection_count_(0),
38 pub_model_states_connection_count_(0),
39 pub_performance_metrics_connection_count_(0),
40 pub_clock_frequency_(0),
41 enable_ros_network_(true)
128 ROS_ERROR_NAMED(
"api_plugin",
"Something other than this gazebo_ros_api plugin started ros::init(...), command line arguments may not be parsed properly.");
136 std::this_thread::sleep_for(std::chrono::microseconds(500*1000));
163 ROS_INFO_NAMED(
"api_plugin",
"Finished loading Gazebo ROS API Plugin.");
180 world_ = gazebo::physics::get_world(world_name);
185 ROS_FATAL_NAMED(
"api_plugin",
"cannot load gazebo ros api server plugin, physics::get_world() fails to return world");
189 gazebonode_ = gazebo::transport::NodePtr(
new gazebo::transport::Node());
202 pub_clock_ =
nh_->advertise<rosgraph_msgs::Clock>(
"/clock", 10);
209 if(!(
nh_->hasParam(
"/use_sim_time")))
210 nh_->setParam(
"/use_sim_time",
true);
213 #if GAZEBO_MAJOR_VERSION >= 8
229 #ifdef GAZEBO_ROS_HAS_PERFORMANCE_METRICS
232 gazebo_msgs::PerformanceMetrics msg_ros;
234 msg_ros.real_time_factor = msg->real_time_factor();
235 for (
auto sensor: msg->sensor())
238 sensor_msgs.sim_update_rate = sensor.sim_update_rate();
239 sensor_msgs.real_update_rate = sensor.real_update_rate();
242 if (sensor.has_fps())
259 static const double timeout = 0.001;
270 ROS_INFO_NAMED(
"api_plugin",
"ROS gazebo topics/services are disabled");
275 std::string spawn_sdf_model_service_name(
"spawn_sdf_model");
277 ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
278 spawn_sdf_model_service_name,
284 std::string spawn_urdf_model_service_name(
"spawn_urdf_model");
286 ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
287 spawn_urdf_model_service_name,
293 std::string delete_model_service_name(
"delete_model");
295 ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteModel>(
296 delete_model_service_name,
302 std::string delete_light_service_name(
"delete_light");
304 ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteLight>(
305 delete_light_service_name,
311 std::string get_model_properties_service_name(
"get_model_properties");
313 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelProperties>(
314 get_model_properties_service_name,
320 std::string get_model_state_service_name(
"get_model_state");
322 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelState>(
323 get_model_state_service_name,
329 std::string get_world_properties_service_name(
"get_world_properties");
331 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetWorldProperties>(
332 get_world_properties_service_name,
338 std::string get_joint_properties_service_name(
"get_joint_properties");
340 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetJointProperties>(
341 get_joint_properties_service_name,
347 std::string get_link_properties_service_name(
"get_link_properties");
349 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkProperties>(
350 get_link_properties_service_name,
356 std::string get_link_state_service_name(
"get_link_state");
358 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkState>(
359 get_link_state_service_name,
365 std::string get_light_properties_service_name(
"get_light_properties");
367 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLightProperties>(
368 get_light_properties_service_name,
374 std::string set_light_properties_service_name(
"set_light_properties");
376 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLightProperties>(
377 set_light_properties_service_name,
383 std::string get_physics_properties_service_name(
"get_physics_properties");
385 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetPhysicsProperties>(
386 get_physics_properties_service_name,
393 ros::AdvertiseOptions::create<gazebo_msgs::LinkStates>(
402 ros::AdvertiseOptions::create<gazebo_msgs::ModelStates>(
409 #ifdef GAZEBO_ROS_HAS_PERFORMANCE_METRICS
412 ros::AdvertiseOptions::create<gazebo_msgs::PerformanceMetrics>(
413 "performance_metrics",10,
414 boost::bind(&GazeboRosApiPlugin::onPerformanceMetricsConnect,
this),
415 boost::bind(&GazeboRosApiPlugin::onPerformanceMetricsDisconnect,
this),
421 std::string set_link_properties_service_name(
"set_link_properties");
423 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkProperties>(
424 set_link_properties_service_name,
430 std::string set_physics_properties_service_name(
"set_physics_properties");
432 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetPhysicsProperties>(
433 set_physics_properties_service_name,
439 std::string set_model_state_service_name(
"set_model_state");
441 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelState>(
442 set_model_state_service_name,
448 std::string set_model_configuration_service_name(
"set_model_configuration");
450 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelConfiguration>(
451 set_model_configuration_service_name,
457 std::string set_joint_properties_service_name(
"set_joint_properties");
459 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointProperties>(
460 set_joint_properties_service_name,
466 std::string set_link_state_service_name(
"set_link_state");
468 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkState>(
469 set_link_state_service_name,
477 ros::SubscribeOptions::create<gazebo_msgs::LinkState>(
485 ros::SubscribeOptions::create<gazebo_msgs::ModelState>(
486 "set_model_state",10,
492 std::string pause_physics_service_name(
"pause_physics");
494 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
495 pause_physics_service_name,
501 std::string unpause_physics_service_name(
"unpause_physics");
503 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
504 unpause_physics_service_name,
510 std::string apply_body_wrench_service_name(
"apply_body_wrench");
512 ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyBodyWrench>(
513 apply_body_wrench_service_name,
519 std::string apply_joint_effort_service_name(
"apply_joint_effort");
521 ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyJointEffort>(
522 apply_joint_effort_service_name,
528 std::string clear_joint_forces_service_name(
"clear_joint_forces");
530 ros::AdvertiseServiceOptions::create<gazebo_msgs::JointRequest>(
531 clear_joint_forces_service_name,
537 std::string clear_body_wrenches_service_name(
"clear_body_wrenches");
539 ros::AdvertiseServiceOptions::create<gazebo_msgs::BodyRequest>(
540 clear_body_wrenches_service_name,
546 std::string reset_simulation_service_name(
"reset_simulation");
548 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
549 reset_simulation_service_name,
555 std::string reset_world_service_name(
"reset_world");
557 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
558 reset_world_service_name,
578 #ifdef GAZEBO_ROS_HAS_PERFORMANCE_METRICS
579 void GazeboRosApiPlugin::onPerformanceMetricsConnect()
585 &GazeboRosApiPlugin::onPerformanceMetrics,
this);
589 void GazeboRosApiPlugin::onPerformanceMetricsDisconnect()
596 ROS_ERROR_NAMED(
"api_plugin",
"One too many disconnect from pub_performance_metrics_ in gazebo_ros.cpp? something weird");
608 ROS_ERROR_NAMED(
"api_plugin",
"One too many disconnect from pub_link_states_ in gazebo_ros.cpp? something weird");
619 ROS_ERROR_NAMED(
"api_plugin",
"One too many disconnect from pub_model_states_ in gazebo_ros.cpp? something weird");
624 gazebo_msgs::SpawnModel::Response &res)
630 std::string model_xml = req.model_xml;
634 ROS_ERROR_NAMED(
"api_plugin",
"SpawnModel: Failure - entity format is invalid.");
636 res.status_message =
"SpawnModel: Failure - entity format is invalid.";
644 std::string open_bracket(
"<?");
645 std::string close_bracket(
"?>");
646 size_t pos1 = model_xml.find(open_bracket,0);
647 size_t pos2 = model_xml.find(close_bracket,0);
648 if (pos1 != std::string::npos && pos2 != std::string::npos)
649 model_xml.replace(pos1,pos2-pos1+2,std::string(
""));
654 std::string open_comment(
"<!--");
655 std::string close_comment(
"-->");
657 while((pos1 = model_xml.find(open_comment,0)) != std::string::npos){
658 size_t pos2 = model_xml.find(close_comment,0);
659 if (pos2 != std::string::npos)
660 model_xml.replace(pos1,pos2-pos1+3,std::string(
""));
666 std::string package_prefix(
"package://");
667 size_t pos1 = model_xml.find(package_prefix,0);
668 while (pos1 != std::string::npos)
670 size_t pos2 = model_xml.find(
"/", pos1+10);
672 if (pos2 == std::string::npos || pos1 >= pos2)
678 std::string package_name = model_xml.substr(pos1+10,pos2-pos1-10);
681 if (package_path.empty())
683 ROS_FATAL_NAMED(
"api_plugin",
"Package[%s] does not have a path",package_name.c_str());
685 res.status_message =
"urdf reference package name does not exist: " + package_name;
688 ROS_DEBUG_ONCE_NAMED(
"api_plugin",
"Package name [%s] has path [%s]", package_name.c_str(), package_path.c_str());
690 model_xml.replace(pos1,(pos2-pos1),package_path);
691 pos1 = model_xml.find(package_prefix, pos1);
696 req.model_xml = model_xml;
703 gazebo_msgs::SpawnModel::Response &res)
706 std::string model_name = req.model_name;
712 ignition::math::Vector3d initial_xyz(req.initial_pose.position.x,req.initial_pose.position.y,req.initial_pose.position.z);
714 ignition::math::Quaterniond initial_q(req.initial_pose.orientation.w,req.initial_pose.orientation.x,req.initial_pose.orientation.y,req.initial_pose.orientation.z);
717 #if GAZEBO_MAJOR_VERSION >= 8
718 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
720 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
725 #if GAZEBO_MAJOR_VERSION >= 8
726 ignition::math::Pose3d frame_pose = frame->WorldPose();
728 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
730 initial_xyz = frame_pose.Pos() + frame_pose.Rot().RotateVector(initial_xyz);
731 initial_q = frame_pose.Rot() * initial_q;
735 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
737 ROS_DEBUG_NAMED(
"api_plugin",
"SpawnModel: reference_frame is empty/world/map, using inertial frame");
742 res.status_message =
"SpawnModel: reference reference_frame not found, did you forget to scope the link by model name?";
747 std::string model_xml = req.model_xml;
755 TiXmlDocument gazebo_model_xml;
756 gazebo_model_xml.Parse(model_xml.c_str());
759 if (
isSDF(model_xml))
769 TiXmlNode* model_tixml = gazebo_model_xml.FirstChild(
"sdf");
770 model_tixml = (!model_tixml) ?
771 gazebo_model_xml.FirstChild(
"gazebo") : model_tixml;
778 ROS_WARN_NAMED(
"api_plugin",
"Unable to add robot namespace to xml");
782 else if (
isURDF(model_xml))
792 TiXmlNode* model_tixml = gazebo_model_xml.FirstChild(
"robot");
799 ROS_WARN_NAMED(
"api_plugin",
"Unable to add robot namespace to xml");
805 ROS_ERROR_NAMED(
"api_plugin",
"GazeboRosApiPlugin SpawnModel Failure: input xml format not recognized");
807 res.status_message =
"GazeboRosApiPlugin SpawnModel Failure: input model_xml not SDF or URDF, or cannot be converted to Gazebo compatible format.";
816 gazebo_msgs::DeleteModel::Response &res)
819 #if GAZEBO_MAJOR_VERSION >= 8
820 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
822 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
826 ROS_ERROR_NAMED(
"api_plugin",
"DeleteModel: model [%s] does not exist",req.model_name.c_str());
828 res.status_message =
"DeleteModel: model does not exist";
833 for (
unsigned int i = 0 ; i < model->GetChildCount(); i ++)
835 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
844 gazebo::physics::Joint_V joints = model->GetJoints();
845 for (
unsigned int i=0;i< joints.size(); i++)
852 gazebo::msgs::Request *msg = gazebo::msgs::CreateRequest(
"entity_delete",req.model_name);
865 res.status_message =
"DeleteModel: Model pushed to delete queue, but delete service timed out waiting for model to disappear from simulation";
870 #if GAZEBO_MAJOR_VERSION >= 8
871 if (!
world_->ModelByName(req.model_name))
break;
873 if (!
world_->GetModel(req.model_name))
break;
876 ROS_DEBUG_NAMED(
"api_plugin",
"Waiting for model deletion (%s)",req.model_name.c_str());
877 std::this_thread::sleep_for(std::chrono::microseconds(1000));
882 res.status_message =
"DeleteModel: successfully deleted model";
887 gazebo_msgs::DeleteLight::Response &res)
889 #if GAZEBO_MAJOR_VERSION >= 8
890 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
892 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
895 if (phy_light == NULL)
898 res.status_message =
"DeleteLight: Requested light " + req.light_name +
" not found!";
902 gazebo::msgs::Request* msg = gazebo::msgs::CreateRequest(
"entity_delete", req.light_name);
909 for (
int i = 0; i < 100; i++)
911 #if GAZEBO_MAJOR_VERSION >= 8
912 phy_light =
world_->LightByName(req.light_name);
914 phy_light =
world_->Light(req.light_name);
916 if (phy_light == NULL)
919 res.status_message =
"DeleteLight: " + req.light_name +
" successfully deleted";
923 std::this_thread::sleep_for(std::chrono::microseconds(100000));
927 res.status_message =
"DeleteLight: Timeout reached while removing light \"" + req.light_name
934 gazebo_msgs::GetModelState::Response &res)
936 #if GAZEBO_MAJOR_VERSION >= 8
937 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
938 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.relative_entity_name);
940 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
941 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.relative_entity_name);
945 ROS_ERROR_NAMED(
"api_plugin",
"GetModelState: model [%s] does not exist",req.model_name.c_str());
947 res.status_message =
"GetModelState: model does not exist";
967 res.header.seq = it->second;
970 res.header.frame_id = req.relative_entity_name;
974 #if GAZEBO_MAJOR_VERSION >= 8
975 ignition::math::Pose3d model_pose = model->WorldPose();
976 ignition::math::Vector3d model_linear_vel = model->WorldLinearVel();
977 ignition::math::Vector3d model_angular_vel = model->WorldAngularVel();
979 ignition::math::Pose3d model_pose = model->GetWorldPose().Ign();
980 ignition::math::Vector3d model_linear_vel = model->GetWorldLinearVel().Ign();
981 ignition::math::Vector3d model_angular_vel = model->GetWorldAngularVel().Ign();
983 ignition::math::Vector3d model_pos = model_pose.Pos();
984 ignition::math::Quaterniond model_rot = model_pose.Rot();
991 #if GAZEBO_MAJOR_VERSION >= 8
992 ignition::math::Pose3d frame_pose = frame->WorldPose();
993 ignition::math::Vector3d frame_vpos = frame->WorldLinearVel();
994 ignition::math::Vector3d frame_veul = frame->WorldAngularVel();
996 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
997 ignition::math::Vector3d frame_vpos = frame->GetWorldLinearVel().Ign();
998 ignition::math::Vector3d frame_veul = frame->GetWorldAngularVel().Ign();
1000 ignition::math::Pose3d model_rel_pose = model_pose - frame_pose;
1001 model_pos = model_rel_pose.Pos();
1002 model_rot = model_rel_pose.Rot();
1004 model_linear_vel = frame_pose.Rot().RotateVectorReverse(model_linear_vel - frame_vpos);
1005 model_angular_vel = frame_pose.Rot().RotateVectorReverse(model_angular_vel - frame_veul);
1008 else if (req.relative_entity_name ==
"" || req.relative_entity_name ==
"world" || req.relative_entity_name ==
"map" || req.relative_entity_name ==
"/map")
1010 ROS_DEBUG_NAMED(
"api_plugin",
"GetModelState: relative_entity_name is empty/world/map, using inertial frame");
1014 res.success =
false;
1015 res.status_message =
"GetModelState: reference relative_entity_name not found, did you forget to scope the body by model name?";
1020 res.pose.position.x = model_pos.X();
1021 res.pose.position.y = model_pos.Y();
1022 res.pose.position.z = model_pos.Z();
1023 res.pose.orientation.w = model_rot.W();
1024 res.pose.orientation.x = model_rot.X();
1025 res.pose.orientation.y = model_rot.Y();
1026 res.pose.orientation.z = model_rot.Z();
1028 res.twist.linear.x = model_linear_vel.X();
1029 res.twist.linear.y = model_linear_vel.Y();
1030 res.twist.linear.z = model_linear_vel.Z();
1031 res.twist.angular.x = model_angular_vel.X();
1032 res.twist.angular.y = model_angular_vel.Y();
1033 res.twist.angular.z = model_angular_vel.Z();
1036 res.status_message =
"GetModelState: got properties";
1043 gazebo_msgs::GetModelProperties::Response &res)
1045 #if GAZEBO_MAJOR_VERSION >= 8
1046 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
1048 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
1052 ROS_ERROR_NAMED(
"api_plugin",
"GetModelProperties: model [%s] does not exist",req.model_name.c_str());
1053 res.success =
false;
1054 res.status_message =
"GetModelProperties: model does not exist";
1060 gazebo::physics::ModelPtr parent_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetParent());
1061 if (parent_model) res.parent_model_name = parent_model->GetName();
1064 res.body_names.clear();
1065 res.geom_names.clear();
1066 for (
unsigned int i = 0 ; i < model->GetChildCount(); i ++)
1068 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
1071 res.body_names.push_back(body->GetName());
1073 for (
unsigned int j = 0; j < body->GetChildCount() ; j++)
1075 gazebo::physics::CollisionPtr geom = boost::dynamic_pointer_cast<gazebo::physics::Collision>(body->GetChild(j));
1077 res.geom_names.push_back(geom->GetName());
1083 res.joint_names.clear();
1085 gazebo::physics::Joint_V joints = model->GetJoints();
1086 for (
unsigned int i=0;i< joints.size(); i++)
1087 res.joint_names.push_back( joints[i]->GetName() );
1090 res.child_model_names.clear();
1091 for (
unsigned int j = 0; j < model->GetChildCount(); j++)
1093 gazebo::physics::ModelPtr child_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetChild(j));
1095 res.child_model_names.push_back(child_model->GetName() );
1099 res.is_static = model->IsStatic();
1102 res.status_message =
"GetModelProperties: got properties";
1109 gazebo_msgs::GetWorldProperties::Response &res)
1111 res.model_names.clear();
1112 #if GAZEBO_MAJOR_VERSION >= 8
1113 res.sim_time =
world_->SimTime().Double();
1114 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1115 res.model_names.push_back(
world_->ModelByIndex(i)->GetName());
1117 res.sim_time =
world_->GetSimTime().Double();
1118 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1119 res.model_names.push_back(
world_->GetModel(i)->GetName());
1121 gzerr <<
"disabling rendering has not been implemented, rendering is always enabled\n";
1122 res.rendering_enabled =
true;
1124 res.status_message =
"GetWorldProperties: got properties";
1129 gazebo_msgs::GetJointProperties::Response &res)
1131 gazebo::physics::JointPtr joint;
1132 #if GAZEBO_MAJOR_VERSION >= 8
1133 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1135 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1137 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1139 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1146 res.success =
false;
1147 res.status_message =
"GetJointProperties: joint not found";
1153 res.type = res.REVOLUTE;
1155 res.damping.clear();
1158 res.position.clear();
1159 #if GAZEBO_MAJOR_VERSION >= 8
1160 res.position.push_back(joint->Position(0));
1162 res.position.push_back(joint->GetAngle(0).Radian());
1166 res.rate.push_back(joint->GetVelocity(0));
1169 res.status_message =
"GetJointProperties: got properties";
1175 gazebo_msgs::GetLinkProperties::Response &res)
1177 #if GAZEBO_MAJOR_VERSION >= 8
1178 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1180 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1184 res.success =
false;
1185 res.status_message =
"GetLinkProperties: link not found, did you forget to scope the link by model name?";
1191 res.gravity_mode = body->GetGravityMode();
1193 gazebo::physics::InertialPtr inertia = body->GetInertial();
1195 #if GAZEBO_MAJOR_VERSION >= 8
1196 res.mass = body->GetInertial()->Mass();
1198 res.ixx = inertia->IXX();
1199 res.iyy = inertia->IYY();
1200 res.izz = inertia->IZZ();
1201 res.ixy = inertia->IXY();
1202 res.ixz = inertia->IXZ();
1203 res.iyz = inertia->IYZ();
1205 ignition::math::Vector3d com = body->GetInertial()->CoG();
1207 res.mass = body->GetInertial()->GetMass();
1209 res.ixx = inertia->GetIXX();
1210 res.iyy = inertia->GetIYY();
1211 res.izz = inertia->GetIZZ();
1212 res.ixy = inertia->GetIXY();
1213 res.ixz = inertia->GetIXZ();
1214 res.iyz = inertia->GetIYZ();
1216 ignition::math::Vector3d com = body->GetInertial()->GetCoG().Ign();
1218 res.com.position.x = com.X();
1219 res.com.position.y = com.Y();
1220 res.com.position.z = com.Z();
1221 res.com.orientation.x = 0;
1222 res.com.orientation.y = 0;
1223 res.com.orientation.z = 0;
1224 res.com.orientation.w = 1;
1227 res.status_message =
"GetLinkProperties: got properties";
1233 gazebo_msgs::GetLinkState::Response &res)
1235 #if GAZEBO_MAJOR_VERSION >= 8
1236 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1237 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
1239 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1240 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
1245 res.success =
false;
1246 res.status_message =
"GetLinkState: link not found, did you forget to scope the link by model name?";
1252 #if GAZEBO_MAJOR_VERSION >= 8
1253 ignition::math::Pose3d body_pose = body->WorldPose();
1254 ignition::math::Vector3d body_vpos = body->WorldLinearVel();
1255 ignition::math::Vector3d body_veul = body->WorldAngularVel();
1257 ignition::math::Pose3d body_pose = body->GetWorldPose().Ign();
1258 ignition::math::Vector3d body_vpos = body->GetWorldLinearVel().Ign();
1259 ignition::math::Vector3d body_veul = body->GetWorldAngularVel().Ign();
1265 #if GAZEBO_MAJOR_VERSION >= 8
1266 ignition::math::Pose3d frame_pose = frame->WorldPose();
1267 ignition::math::Vector3d frame_vpos = frame->WorldLinearVel();
1268 ignition::math::Vector3d frame_veul = frame->WorldAngularVel();
1270 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
1271 ignition::math::Vector3d frame_vpos = frame->GetWorldLinearVel().Ign();
1272 ignition::math::Vector3d frame_veul = frame->GetWorldAngularVel().Ign();
1274 body_pose = body_pose - frame_pose;
1276 body_vpos = frame_pose.Rot().RotateVectorReverse(body_vpos - frame_vpos);
1277 body_veul = frame_pose.Rot().RotateVectorReverse(body_veul - frame_veul);
1280 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
1282 ROS_DEBUG_NAMED(
"api_plugin",
"GetLinkState: reference_frame is empty/world/map, using inertial frame");
1286 res.success =
false;
1287 res.status_message =
"GetLinkState: reference reference_frame not found, did you forget to scope the link by model name?";
1291 res.link_state.link_name = req.link_name;
1292 res.link_state.pose.position.x = body_pose.Pos().X();
1293 res.link_state.pose.position.y = body_pose.Pos().Y();
1294 res.link_state.pose.position.z = body_pose.Pos().Z();
1295 res.link_state.pose.orientation.x = body_pose.Rot().X();
1296 res.link_state.pose.orientation.y = body_pose.Rot().Y();
1297 res.link_state.pose.orientation.z = body_pose.Rot().Z();
1298 res.link_state.pose.orientation.w = body_pose.Rot().W();
1299 res.link_state.twist.linear.x = body_vpos.X();
1300 res.link_state.twist.linear.y = body_vpos.Y();
1301 res.link_state.twist.linear.z = body_vpos.Z();
1302 res.link_state.twist.angular.x = body_veul.X();
1303 res.link_state.twist.angular.y = body_veul.Y();
1304 res.link_state.twist.angular.z = body_veul.Z();
1305 res.link_state.reference_frame = req.reference_frame;
1308 res.status_message =
"GetLinkState: got state";
1313 gazebo_msgs::GetLightProperties::Response &res)
1315 #if GAZEBO_MAJOR_VERSION >= 8
1316 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
1318 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
1321 if (phy_light == NULL)
1323 res.success =
false;
1324 res.status_message =
"getLightProperties: Requested light " + req.light_name +
" not found!";
1328 gazebo::msgs::Light light;
1329 phy_light->FillMsg(light);
1331 res.diffuse.r = light.diffuse().r();
1332 res.diffuse.g = light.diffuse().g();
1333 res.diffuse.b = light.diffuse().b();
1334 res.diffuse.a = light.diffuse().a();
1336 res.attenuation_constant = light.attenuation_constant();
1337 res.attenuation_linear = light.attenuation_linear();
1338 res.attenuation_quadratic = light.attenuation_quadratic();
1347 gazebo_msgs::SetLightProperties::Response &res)
1349 #if GAZEBO_MAJOR_VERSION >= 8
1350 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
1352 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
1355 if (phy_light == NULL)
1357 res.success =
false;
1358 res.status_message =
"setLightProperties: Requested light " + req.light_name +
" not found!";
1362 gazebo::msgs::Light light;
1364 phy_light->FillMsg(light);
1366 light.set_cast_shadows(req.cast_shadows);
1368 light.mutable_diffuse()->set_r(req.diffuse.r);
1369 light.mutable_diffuse()->set_g(req.diffuse.g);
1370 light.mutable_diffuse()->set_b(req.diffuse.b);
1371 light.mutable_diffuse()->set_a(req.diffuse.a);
1373 light.mutable_specular()->set_r(req.specular.r);
1374 light.mutable_specular()->set_g(req.specular.g);
1375 light.mutable_specular()->set_b(req.specular.b);
1376 light.mutable_specular()->set_a(req.specular.a);
1378 light.set_attenuation_constant(req.attenuation_constant);
1379 light.set_attenuation_linear(req.attenuation_linear);
1380 light.set_attenuation_quadratic(req.attenuation_quadratic);
1382 light.mutable_direction()->set_x(req.direction.x);
1383 light.mutable_direction()->set_y(req.direction.y);
1384 light.mutable_direction()->set_z(req.direction.z);
1386 light.mutable_pose()->mutable_position()->set_x(req.pose.position.x);
1387 light.mutable_pose()->mutable_position()->set_y(req.pose.position.y);
1388 light.mutable_pose()->mutable_position()->set_z(req.pose.position.z);
1389 light.mutable_pose()->mutable_orientation()->set_w(req.pose.orientation.w);
1390 light.mutable_pose()->mutable_orientation()->set_x(req.pose.orientation.x);
1391 light.mutable_pose()->mutable_orientation()->set_y(req.pose.orientation.y);
1392 light.mutable_pose()->mutable_orientation()->set_z(req.pose.orientation.z);
1403 gazebo_msgs::SetLinkProperties::Response &res)
1405 #if GAZEBO_MAJOR_VERSION >= 8
1406 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1408 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1412 res.success =
false;
1413 res.status_message =
"SetLinkProperties: link not found, did you forget to scope the link by model name?";
1418 gazebo::physics::InertialPtr mass = body->GetInertial();
1421 mass->SetCoG(ignition::math::Vector3d(req.com.position.x,req.com.position.y,req.com.position.z));
1422 mass->SetInertiaMatrix(req.ixx,req.iyy,req.izz,req.ixy,req.ixz,req.iyz);
1423 mass->SetMass(req.mass);
1424 body->SetGravityMode(req.gravity_mode);
1427 res.status_message =
"SetLinkProperties: properties set";
1433 gazebo_msgs::SetPhysicsProperties::Response &res)
1436 bool is_paused =
world_->IsPaused();
1438 world_->SetGravity(ignition::math::Vector3d(req.gravity.x,req.gravity.y,req.gravity.z));
1441 #if GAZEBO_MAJOR_VERSION >= 8
1442 gazebo::physics::PhysicsEnginePtr pe = (
world_->Physics());
1444 gazebo::physics::PhysicsEnginePtr pe = (
world_->GetPhysicsEngine());
1446 pe->SetMaxStepSize(req.time_step);
1447 pe->SetRealTimeUpdateRate(req.max_update_rate);
1449 if (pe->GetType() ==
"ode")
1452 pe->SetAutoDisableFlag(req.ode_config.auto_disable_bodies);
1453 pe->SetParam(
"precon_iters",
int(req.ode_config.sor_pgs_precon_iters));
1454 pe->SetParam(
"iters",
int(req.ode_config.sor_pgs_iters));
1455 pe->SetParam(
"sor", req.ode_config.sor_pgs_w);
1456 pe->SetParam(
"cfm", req.ode_config.cfm);
1457 pe->SetParam(
"erp", req.ode_config.erp);
1458 pe->SetParam(
"contact_surface_layer",
1459 req.ode_config.contact_surface_layer);
1460 pe->SetParam(
"contact_max_correcting_vel",
1461 req.ode_config.contact_max_correcting_vel);
1462 pe->SetParam(
"max_contacts",
int(req.ode_config.max_contacts));
1464 world_->SetPaused(is_paused);
1467 res.status_message =
"physics engine updated";
1472 ROS_ERROR_NAMED(
"api_plugin",
"ROS set_physics_properties service call does not yet support physics engine [%s].", pe->GetType().c_str());
1473 res.success =
false;
1474 res.status_message =
"Physics engine [" + pe->GetType() +
"]: set_physics_properties not supported.";
1480 gazebo_msgs::GetPhysicsProperties::Response &res)
1483 #if GAZEBO_MAJOR_VERSION >= 8
1484 gazebo::physics::PhysicsEnginePtr pe = (
world_->Physics());
1486 gazebo::physics::PhysicsEnginePtr pe = (
world_->GetPhysicsEngine());
1488 res.time_step = pe->GetMaxStepSize();
1489 res.pause =
world_->IsPaused();
1490 res.max_update_rate = pe->GetRealTimeUpdateRate();
1491 ignition::math::Vector3d gravity =
world_->Gravity();
1492 res.gravity.x = gravity.X();
1493 res.gravity.y = gravity.Y();
1494 res.gravity.z = gravity.Z();
1497 if (pe->GetType() ==
"ode")
1499 res.ode_config.auto_disable_bodies =
1500 pe->GetAutoDisableFlag();
1501 res.ode_config.sor_pgs_precon_iters = boost::any_cast<int>(
1502 pe->GetParam(
"precon_iters"));
1503 res.ode_config.sor_pgs_iters = boost::any_cast<int>(
1504 pe->GetParam(
"iters"));
1505 res.ode_config.sor_pgs_w = boost::any_cast<double>(
1506 pe->GetParam(
"sor"));
1507 res.ode_config.contact_surface_layer = boost::any_cast<double>(
1508 pe->GetParam(
"contact_surface_layer"));
1509 res.ode_config.contact_max_correcting_vel = boost::any_cast<double>(
1510 pe->GetParam(
"contact_max_correcting_vel"));
1511 res.ode_config.cfm = boost::any_cast<double>(
1512 pe->GetParam(
"cfm"));
1513 res.ode_config.erp = boost::any_cast<double>(
1514 pe->GetParam(
"erp"));
1515 res.ode_config.max_contacts = boost::any_cast<int>(
1516 pe->GetParam(
"max_contacts"));
1519 res.status_message =
"GetPhysicsProperties: got properties";
1524 ROS_ERROR_NAMED(
"api_plugin",
"ROS get_physics_properties service call does not yet support physics engine [%s].", pe->GetType().c_str());
1525 res.success =
false;
1526 res.status_message =
"Physics engine [" + pe->GetType() +
"]: get_physics_properties not supported.";
1532 gazebo_msgs::SetJointProperties::Response &res)
1535 gazebo::physics::JointPtr joint;
1536 #if GAZEBO_MAJOR_VERSION >= 8
1537 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1539 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1541 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1543 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1550 res.success =
false;
1551 res.status_message =
"SetJointProperties: joint not found";
1556 for(
unsigned int i=0;i< req.ode_joint_config.damping.size();i++)
1557 joint->SetDamping(i,req.ode_joint_config.damping[i]);
1558 for(
unsigned int i=0;i< req.ode_joint_config.hiStop.size();i++)
1559 joint->SetParam(
"hi_stop",i,req.ode_joint_config.hiStop[i]);
1560 for(
unsigned int i=0;i< req.ode_joint_config.loStop.size();i++)
1561 joint->SetParam(
"lo_stop",i,req.ode_joint_config.loStop[i]);
1562 for(
unsigned int i=0;i< req.ode_joint_config.erp.size();i++)
1563 joint->SetParam(
"erp",i,req.ode_joint_config.erp[i]);
1564 for(
unsigned int i=0;i< req.ode_joint_config.cfm.size();i++)
1565 joint->SetParam(
"cfm",i,req.ode_joint_config.cfm[i]);
1566 for(
unsigned int i=0;i< req.ode_joint_config.stop_erp.size();i++)
1567 joint->SetParam(
"stop_erp",i,req.ode_joint_config.stop_erp[i]);
1568 for(
unsigned int i=0;i< req.ode_joint_config.stop_cfm.size();i++)
1569 joint->SetParam(
"stop_cfm",i,req.ode_joint_config.stop_cfm[i]);
1570 for(
unsigned int i=0;i< req.ode_joint_config.fudge_factor.size();i++)
1571 joint->SetParam(
"fudge_factor",i,req.ode_joint_config.fudge_factor[i]);
1572 for(
unsigned int i=0;i< req.ode_joint_config.fmax.size();i++)
1573 joint->SetParam(
"fmax",i,req.ode_joint_config.fmax[i]);
1574 for(
unsigned int i=0;i< req.ode_joint_config.vel.size();i++)
1575 joint->SetParam(
"vel",i,req.ode_joint_config.vel[i]);
1578 res.status_message =
"SetJointProperties: properties set";
1584 gazebo_msgs::SetModelState::Response &res)
1586 ignition::math::Vector3d target_pos(req.model_state.pose.position.x,req.model_state.pose.position.y,req.model_state.pose.position.z);
1587 ignition::math::Quaterniond target_rot(req.model_state.pose.orientation.w,req.model_state.pose.orientation.x,req.model_state.pose.orientation.y,req.model_state.pose.orientation.z);
1588 target_rot.Normalize();
1589 ignition::math::Pose3d target_pose(target_pos,target_rot);
1590 ignition::math::Vector3d target_pos_dot(req.model_state.twist.linear.x,req.model_state.twist.linear.y,req.model_state.twist.linear.z);
1591 ignition::math::Vector3d target_rot_dot(req.model_state.twist.angular.x,req.model_state.twist.angular.y,req.model_state.twist.angular.z);
1593 #if GAZEBO_MAJOR_VERSION >= 8
1594 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_state.model_name);
1596 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_state.model_name);
1600 ROS_ERROR_NAMED(
"api_plugin",
"Updating ModelState: model [%s] does not exist",req.model_state.model_name.c_str());
1601 res.success =
false;
1602 res.status_message =
"SetModelState: model does not exist";
1607 #if GAZEBO_MAJOR_VERSION >= 8
1608 gazebo::physics::EntityPtr relative_entity =
world_->EntityByName(req.model_state.reference_frame);
1610 gazebo::physics::EntityPtr relative_entity =
world_->GetEntity(req.model_state.reference_frame);
1612 if (relative_entity)
1614 #if GAZEBO_MAJOR_VERSION >= 8
1615 ignition::math::Pose3d frame_pose = relative_entity->WorldPose();
1617 ignition::math::Pose3d frame_pose = relative_entity->GetWorldPose().Ign();
1620 target_pose = target_pose + frame_pose;
1624 target_pos_dot = frame_pose.Rot().RotateVector(target_pos_dot);
1625 target_rot_dot = frame_pose.Rot().RotateVector(target_rot_dot);
1628 else if (req.model_state.reference_frame ==
"" || req.model_state.reference_frame ==
"world" || req.model_state.reference_frame ==
"map" || req.model_state.reference_frame ==
"/map" )
1630 ROS_DEBUG_NAMED(
"api_plugin",
"Updating ModelState: reference frame is empty/world/map, usig inertial frame");
1634 ROS_ERROR_NAMED(
"api_plugin",
"Updating ModelState: for model[%s], specified reference frame entity [%s] does not exist",
1635 req.model_state.model_name.c_str(),req.model_state.reference_frame.c_str());
1636 res.success =
false;
1637 res.status_message =
"SetModelState: specified reference frame entity does not exist";
1642 bool is_paused =
world_->IsPaused();
1644 model->SetWorldPose(target_pose);
1645 world_->SetPaused(is_paused);
1646 #if GAZEBO_MAJOR_VERSION >= 8
1654 model->SetLinearVel(target_pos_dot);
1655 model->SetAngularVel(target_rot_dot);
1658 res.status_message =
"SetModelState: set model state done";
1665 gazebo_msgs::SetModelState::Response res;
1666 gazebo_msgs::SetModelState::Request req;
1667 req.model_state = *model_state;
1672 gazebo_msgs::ApplyJointEffort::Response &res)
1674 gazebo::physics::JointPtr joint;
1675 #if GAZEBO_MAJOR_VERSION >= 8
1676 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1678 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1680 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1682 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1688 fjj->
force = req.effort;
1690 #if GAZEBO_MAJOR_VERSION >= 8
1703 res.status_message =
"ApplyJointEffort: effort set";
1708 res.success =
false;
1709 res.status_message =
"ApplyJointEffort: joint not found";
1721 world_->ResetEntities(gazebo::physics::Base::MODEL);
1733 world_->SetPaused(
false);
1738 gazebo_msgs::JointRequest::Response &res)
1751 if ((*iter)->joint->GetName() == joint_name)
1766 gazebo_msgs::BodyRequest::Response &res)
1780 if ((*iter)->body->GetScopedName() == body_name)
1795 gazebo_msgs::SetModelConfiguration::Response &res)
1797 std::string gazebo_model_name = req.model_name;
1800 #if GAZEBO_MAJOR_VERSION >= 8
1801 gazebo::physics::ModelPtr gazebo_model =
world_->ModelByName(req.model_name);
1803 gazebo::physics::ModelPtr gazebo_model =
world_->GetModel(req.model_name);
1807 ROS_ERROR_NAMED(
"api_plugin",
"SetModelConfiguration: model [%s] does not exist",gazebo_model_name.c_str());
1808 res.success =
false;
1809 res.status_message =
"SetModelConfiguration: model does not exist";
1813 if (req.joint_names.size() == req.joint_positions.size())
1815 std::map<std::string, double> joint_position_map;
1816 for (
unsigned int i = 0; i < req.joint_names.size(); i++)
1818 joint_position_map[req.joint_names[i]] = req.joint_positions[i];
1822 bool is_paused =
world_->IsPaused();
1823 if (!is_paused)
world_->SetPaused(
true);
1825 gazebo_model->SetJointPositions(joint_position_map);
1828 world_->SetPaused(is_paused);
1831 res.status_message =
"SetModelConfiguration: success";
1836 res.success =
false;
1837 res.status_message =
"SetModelConfiguration: joint name and position list have different lengths";
1843 gazebo_msgs::SetLinkState::Response &res)
1845 #if GAZEBO_MAJOR_VERSION >= 8
1846 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_state.link_name));
1847 gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_state.reference_frame));
1849 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_state.link_name));
1850 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.link_state.reference_frame);
1854 ROS_ERROR_NAMED(
"api_plugin",
"Updating LinkState: link [%s] does not exist",req.link_state.link_name.c_str());
1855 res.success =
false;
1856 res.status_message =
"SetLinkState: link does not exist";
1863 ignition::math::Vector3d target_pos(req.link_state.pose.position.x,req.link_state.pose.position.y,req.link_state.pose.position.z);
1864 ignition::math::Quaterniond target_rot(req.link_state.pose.orientation.w,req.link_state.pose.orientation.x,req.link_state.pose.orientation.y,req.link_state.pose.orientation.z);
1865 ignition::math::Pose3d target_pose(target_pos,target_rot);
1866 ignition::math::Vector3d target_linear_vel(req.link_state.twist.linear.x,req.link_state.twist.linear.y,req.link_state.twist.linear.z);
1867 ignition::math::Vector3d target_angular_vel(req.link_state.twist.angular.x,req.link_state.twist.angular.y,req.link_state.twist.angular.z);
1871 #if GAZEBO_MAJOR_VERSION >= 8
1872 ignition::math::Pose3d frame_pose = frame->WorldPose();
1873 ignition::math::Vector3d frame_linear_vel = frame->WorldLinearVel();
1874 ignition::math::Vector3d frame_angular_vel = frame->WorldAngularVel();
1876 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
1877 ignition::math::Vector3d frame_linear_vel = frame->GetWorldLinearVel().Ign();
1878 ignition::math::Vector3d frame_angular_vel = frame->GetWorldAngularVel().Ign();
1880 ignition::math::Vector3d frame_pos = frame_pose.Pos();
1881 ignition::math::Quaterniond frame_rot = frame_pose.Rot();
1884 target_pose = target_pose + frame_pose;
1886 target_linear_vel -= frame_linear_vel;
1887 target_angular_vel -= frame_angular_vel;
1889 else if (req.link_state.reference_frame ==
"" || req.link_state.reference_frame ==
"world" || req.link_state.reference_frame ==
"map" || req.link_state.reference_frame ==
"/map")
1891 ROS_INFO_NAMED(
"api_plugin",
"Updating LinkState: reference_frame is empty/world/map, using inertial frame");
1895 ROS_ERROR_NAMED(
"api_plugin",
"Updating LinkState: reference_frame is not a valid entity name");
1896 res.success =
false;
1897 res.status_message =
"SetLinkState: failed";
1904 bool is_paused =
world_->IsPaused();
1905 if (!is_paused)
world_->SetPaused(
true);
1906 body->SetWorldPose(target_pose);
1907 world_->SetPaused(is_paused);
1910 body->SetLinearVel(target_linear_vel);
1911 body->SetAngularVel(target_angular_vel);
1914 res.status_message =
"SetLinkState: success";
1920 gazebo_msgs::SetLinkState::Request req;
1921 gazebo_msgs::SetLinkState::Response res;
1922 req.link_state = *link_state;
1927 const ignition::math::Vector3d &reference_force,
1928 const ignition::math::Vector3d &reference_torque,
1929 const ignition::math::Pose3d &target_to_reference )
1932 target_force = target_to_reference.Rot().RotateVector(reference_force);
1934 target_torque = target_to_reference.Rot().RotateVector(reference_torque);
1937 target_torque = target_torque + target_to_reference.Pos().Cross(target_force);
1941 gazebo_msgs::ApplyBodyWrench::Response &res)
1943 #if GAZEBO_MAJOR_VERSION >= 8
1944 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.body_name));
1945 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
1947 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.body_name));
1948 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
1952 ROS_ERROR_NAMED(
"api_plugin",
"ApplyBodyWrench: body [%s] does not exist",req.body_name.c_str());
1953 res.success =
false;
1954 res.status_message =
"ApplyBodyWrench: body does not exist";
1959 ignition::math::Vector3d reference_force(req.wrench.force.x,req.wrench.force.y,req.wrench.force.z);
1960 ignition::math::Vector3d reference_torque(req.wrench.torque.x,req.wrench.torque.y,req.wrench.torque.z);
1961 ignition::math::Vector3d reference_point(req.reference_point.x,req.reference_point.y,req.reference_point.z);
1963 ignition::math::Vector3d target_force;
1964 ignition::math::Vector3d target_torque;
1968 reference_torque = reference_torque + reference_point.Cross(reference_force);
1979 #if GAZEBO_MAJOR_VERSION >= 8
1980 ignition::math::Pose3d framePose = frame->WorldPose();
1981 ignition::math::Pose3d bodyPose = body->WorldPose();
1983 ignition::math::Pose3d framePose = frame->GetWorldPose().Ign();
1984 ignition::math::Pose3d bodyPose = body->GetWorldPose().Ign();
1986 ignition::math::Pose3d target_to_reference = framePose - bodyPose;
1987 ROS_DEBUG_NAMED(
"api_plugin",
"reference frame for applied wrench: [%f %f %f, %f %f %f]-[%f %f %f, %f %f %f]=[%f %f %f, %f %f %f]",
1991 bodyPose.Rot().Euler().X(),
1992 bodyPose.Rot().Euler().Y(),
1993 bodyPose.Rot().Euler().Z(),
1994 framePose.Pos().X(),
1995 framePose.Pos().Y(),
1996 framePose.Pos().Z(),
1997 framePose.Rot().Euler().X(),
1998 framePose.Rot().Euler().Y(),
1999 framePose.Rot().Euler().Z(),
2000 target_to_reference.Pos().X(),
2001 target_to_reference.Pos().Y(),
2002 target_to_reference.Pos().Z(),
2003 target_to_reference.Rot().Euler().X(),
2004 target_to_reference.Rot().Euler().Y(),
2005 target_to_reference.Rot().Euler().Z()
2007 transformWrench(target_force, target_torque, reference_force, reference_torque, target_to_reference);
2008 ROS_ERROR_NAMED(
"api_plugin",
"wrench defined as [%s]:[%f %f %f, %f %f %f] --> applied as [%s]:[%f %f %f, %f %f %f]",
2009 frame->GetName().c_str(),
2010 reference_force.X(),
2011 reference_force.Y(),
2012 reference_force.Z(),
2013 reference_torque.X(),
2014 reference_torque.Y(),
2015 reference_torque.Z(),
2016 body->GetName().c_str(),
2026 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
2028 ROS_INFO_NAMED(
"api_plugin",
"ApplyBodyWrench: reference_frame is empty/world/map, using inertial frame, transferring from body relative to inertial frame");
2030 #if GAZEBO_MAJOR_VERSION >= 8
2031 ignition::math::Pose3d target_to_reference = body->WorldPose();
2033 ignition::math::Pose3d target_to_reference = body->GetWorldPose().Ign();
2035 target_force = reference_force;
2036 target_torque = reference_torque;
2041 ROS_ERROR_NAMED(
"api_plugin",
"ApplyBodyWrench: reference_frame is not a valid entity name");
2042 res.success =
false;
2043 res.status_message =
"ApplyBodyWrench: reference_frame not found";
2053 wej->
force = target_force;
2054 wej->
torque = target_torque;
2056 #if GAZEBO_MAJOR_VERSION >= 8
2069 res.status_message =
"";
2075 TiXmlDocument doc_in;
2076 doc_in.Parse(model_xml.c_str());
2077 if (doc_in.FirstChild(
"robot"))
2086 TiXmlDocument doc_in;
2087 doc_in.Parse(model_xml.c_str());
2088 if (doc_in.FirstChild(
"gazebo") ||
2089 doc_in.FirstChild(
"sdf"))
2103 #if GAZEBO_MAJOR_VERSION >= 8
2108 if (simTime >= (*iter)->start_time)
2109 if (simTime <= (*iter)->start_time+(*iter)->duration ||
2110 (*iter)->duration.
toSec() < 0.0)
2114 (*iter)->body->SetForce((*iter)->force);
2115 (*iter)->body->SetTorque((*iter)->torque);
2118 (*iter)->duration.fromSec(0.0);
2121 if (simTime > (*iter)->start_time+(*iter)->duration &&
2122 (*iter)->duration.
toSec() >= 0.0)
2142 #if GAZEBO_MAJOR_VERSION >= 8
2147 if (simTime >= (*iter)->start_time)
2148 if (simTime <= (*iter)->start_time+(*iter)->duration ||
2149 (*iter)->duration.
toSec() < 0.0)
2152 (*iter)->joint->SetForce(0,(*iter)->force);
2154 (*iter)->duration.fromSec(0.0);
2157 if (simTime > (*iter)->start_time+(*iter)->duration &&
2158 (*iter)->duration.
toSec() >= 0.0)
2171 #if GAZEBO_MAJOR_VERSION >= 8
2172 gazebo::common::Time sim_time =
world_->SimTime();
2174 gazebo::common::Time sim_time =
world_->GetSimTime();
2179 #if GAZEBO_MAJOR_VERSION >= 8
2180 gazebo::common::Time currentTime =
world_->SimTime();
2182 gazebo::common::Time currentTime =
world_->GetSimTime();
2184 rosgraph_msgs::Clock ros_time_;
2185 ros_time_.clock.fromSec(currentTime.Double());
2193 gazebo_msgs::LinkStates link_states;
2196 #if GAZEBO_MAJOR_VERSION >= 8
2197 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
2199 gazebo::physics::ModelPtr model =
world_->ModelByIndex(i);
2201 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
2203 gazebo::physics::ModelPtr model =
world_->GetModel(i);
2206 for (
unsigned int j = 0 ; j < model->GetChildCount(); j ++)
2208 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(j));
2212 link_states.name.push_back(body->GetScopedName());
2213 geometry_msgs::Pose pose;
2214 #if GAZEBO_MAJOR_VERSION >= 8
2215 ignition::math::Pose3d body_pose = body->WorldPose();
2216 ignition::math::Vector3d linear_vel = body->WorldLinearVel();
2217 ignition::math::Vector3d angular_vel = body->WorldAngularVel();
2219 ignition::math::Pose3d body_pose = body->GetWorldPose().Ign();
2220 ignition::math::Vector3d linear_vel = body->GetWorldLinearVel().Ign();
2221 ignition::math::Vector3d angular_vel = body->GetWorldAngularVel().Ign();
2223 ignition::math::Vector3d pos = body_pose.Pos();
2224 ignition::math::Quaterniond rot = body_pose.Rot();
2225 pose.position.x = pos.X();
2226 pose.position.y = pos.Y();
2227 pose.position.z = pos.Z();
2228 pose.orientation.w = rot.W();
2229 pose.orientation.x = rot.X();
2230 pose.orientation.y = rot.Y();
2231 pose.orientation.z = rot.Z();
2232 link_states.pose.push_back(pose);
2233 geometry_msgs::Twist twist;
2234 twist.linear.x = linear_vel.X();
2235 twist.linear.y = linear_vel.Y();
2236 twist.linear.z = linear_vel.Z();
2237 twist.angular.x = angular_vel.X();
2238 twist.angular.y = angular_vel.Y();
2239 twist.angular.z = angular_vel.Z();
2240 link_states.twist.push_back(twist);
2250 gazebo_msgs::ModelStates model_states;
2253 #if GAZEBO_MAJOR_VERSION >= 8
2254 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
2256 gazebo::physics::ModelPtr model =
world_->ModelByIndex(i);
2257 ignition::math::Pose3d model_pose = model->WorldPose();
2258 ignition::math::Vector3d linear_vel = model->WorldLinearVel();
2259 ignition::math::Vector3d angular_vel = model->WorldAngularVel();
2261 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
2263 gazebo::physics::ModelPtr model =
world_->GetModel(i);
2264 ignition::math::Pose3d model_pose = model->GetWorldPose().Ign();
2265 ignition::math::Vector3d linear_vel = model->GetWorldLinearVel().Ign();
2266 ignition::math::Vector3d angular_vel = model->GetWorldAngularVel().Ign();
2268 ignition::math::Vector3d pos = model_pose.Pos();
2269 ignition::math::Quaterniond rot = model_pose.Rot();
2270 geometry_msgs::Pose pose;
2271 pose.position.x = pos.X();
2272 pose.position.y = pos.Y();
2273 pose.position.z = pos.Z();
2274 pose.orientation.w = rot.W();
2275 pose.orientation.x = rot.X();
2276 pose.orientation.y = rot.Y();
2277 pose.orientation.z = rot.Z();
2278 model_states.pose.push_back(pose);
2279 model_states.name.push_back(model->GetName());
2280 geometry_msgs::Twist twist;
2281 twist.linear.x = linear_vel.X();
2282 twist.linear.y = linear_vel.Y();
2283 twist.linear.z = linear_vel.Z();
2284 twist.angular.x = angular_vel.X();
2285 twist.angular.y = angular_vel.Y();
2286 twist.angular.z = angular_vel.Z();
2287 model_states.twist.push_back(twist);
2296 gazebo_msgs::GetPhysicsProperties srv;
2299 config.time_step = srv.response.time_step;
2300 config.max_update_rate = srv.response.max_update_rate;
2301 config.gravity_x = srv.response.gravity.x;
2302 config.gravity_y = srv.response.gravity.y;
2303 config.gravity_z = srv.response.gravity.z;
2304 config.auto_disable_bodies = srv.response.ode_config.auto_disable_bodies;
2305 config.sor_pgs_precon_iters = srv.response.ode_config.sor_pgs_precon_iters;
2306 config.sor_pgs_iters = srv.response.ode_config.sor_pgs_iters;
2307 config.sor_pgs_rms_error_tol = srv.response.ode_config.sor_pgs_rms_error_tol;
2308 config.sor_pgs_w = srv.response.ode_config.sor_pgs_w;
2309 config.contact_surface_layer = srv.response.ode_config.contact_surface_layer;
2310 config.contact_max_correcting_vel = srv.response.ode_config.contact_max_correcting_vel;
2311 config.cfm = srv.response.ode_config.cfm;
2312 config.erp = srv.response.ode_config.erp;
2313 config.max_contacts = srv.response.ode_config.max_contacts;
2318 bool changed =
false;
2319 gazebo_msgs::GetPhysicsProperties srv;
2323 if (config.time_step != srv.response.time_step) changed =
true;
2324 if (config.max_update_rate != srv.response.max_update_rate) changed =
true;
2325 if (config.gravity_x != srv.response.gravity.x) changed =
true;
2326 if (config.gravity_y != srv.response.gravity.y) changed =
true;
2327 if (config.gravity_z != srv.response.gravity.z) changed =
true;
2328 if (config.auto_disable_bodies != srv.response.ode_config.auto_disable_bodies) changed =
true;
2329 if ((uint32_t)config.sor_pgs_precon_iters != srv.response.ode_config.sor_pgs_precon_iters) changed =
true;
2330 if ((uint32_t)config.sor_pgs_iters != srv.response.ode_config.sor_pgs_iters) changed =
true;
2331 if (config.sor_pgs_rms_error_tol != srv.response.ode_config.sor_pgs_rms_error_tol) changed =
true;
2332 if (config.sor_pgs_w != srv.response.ode_config.sor_pgs_w) changed =
true;
2333 if (config.contact_surface_layer != srv.response.ode_config.contact_surface_layer) changed =
true;
2334 if (config.contact_max_correcting_vel != srv.response.ode_config.contact_max_correcting_vel) changed =
true;
2335 if (config.cfm != srv.response.ode_config.cfm) changed =
true;
2336 if (config.erp != srv.response.ode_config.erp) changed =
true;
2337 if ((uint32_t)config.max_contacts != srv.response.ode_config.max_contacts) changed =
true;
2342 gazebo_msgs::SetPhysicsProperties srv;
2343 srv.request.time_step = config.time_step ;
2344 srv.request.max_update_rate = config.max_update_rate ;
2345 srv.request.gravity.x = config.gravity_x ;
2346 srv.request.gravity.y = config.gravity_y ;
2347 srv.request.gravity.z = config.gravity_z ;
2348 srv.request.ode_config.auto_disable_bodies = config.auto_disable_bodies ;
2349 srv.request.ode_config.sor_pgs_precon_iters = config.sor_pgs_precon_iters ;
2350 srv.request.ode_config.sor_pgs_iters = config.sor_pgs_iters ;
2351 srv.request.ode_config.sor_pgs_rms_error_tol = config.sor_pgs_rms_error_tol ;
2352 srv.request.ode_config.sor_pgs_w = config.sor_pgs_w ;
2353 srv.request.ode_config.contact_surface_layer = config.contact_surface_layer ;
2354 srv.request.ode_config.contact_max_correcting_vel = config.contact_max_correcting_vel ;
2355 srv.request.ode_config.cfm = config.cfm ;
2356 srv.request.ode_config.erp = config.erp ;
2357 srv.request.ode_config.max_contacts = config.max_contacts ;
2359 ROS_INFO_NAMED(
"api_plugin",
"physics dynamics reconfigure update complete");
2361 ROS_INFO_NAMED(
"api_plugin",
"physics dynamics reconfigure complete");
2379 ROS_INFO_NAMED(
"api_plugin",
"Physics dynamic reconfigure ready.");
2388 std::string open_bracket(
"<?");
2389 std::string close_bracket(
"?>");
2390 size_t pos1 = model_xml.find(open_bracket,0);
2391 size_t pos2 = model_xml.find(close_bracket,0);
2392 if (pos1 != std::string::npos && pos2 != std::string::npos)
2393 model_xml.replace(pos1,pos2-pos1+2,std::string(
""));
2397 const std::string &model_name,
2398 const ignition::math::Vector3d &initial_xyz,
2399 const ignition::math::Quaterniond &initial_q)
2404 TiXmlElement* pose_element;
2407 TiXmlElement* gazebo_tixml = gazebo_model_xml.FirstChildElement(
"sdf");
2410 ROS_WARN_NAMED(
"api_plugin",
"Could not find <sdf> element in sdf, so name and initial position cannot be applied");
2415 TiXmlElement* model_tixml = gazebo_tixml->FirstChildElement(
"model");
2419 if (model_tixml->Attribute(
"name") != NULL)
2422 model_tixml->RemoveAttribute(
"name");
2425 model_tixml->SetAttribute(
"name",model_name);
2430 TiXmlElement* world_tixml = gazebo_tixml->FirstChildElement(
"world");
2433 ROS_WARN_NAMED(
"api_plugin",
"Could not find <model> or <world> element in sdf, so name and initial position cannot be applied");
2437 model_tixml = world_tixml->FirstChildElement(
"include");
2440 ROS_WARN_NAMED(
"api_plugin",
"Could not find <include> element in sdf, so name and initial position cannot be applied");
2445 TiXmlElement* name_tixml = model_tixml->FirstChildElement(
"name");
2449 name_tixml =
new TiXmlElement(
"name");
2450 model_tixml->LinkEndChild(name_tixml);
2454 TiXmlText* text =
new TiXmlText(model_name);
2455 name_tixml->LinkEndChild( text );
2460 pose_element = model_tixml->FirstChildElement(
"pose");
2461 ignition::math::Pose3d model_pose;
2468 model_pose = this->
parsePose(pose_element->GetText());
2469 model_tixml->RemoveChild(pose_element);
2475 ignition::math::Pose3d new_model_pose = model_pose + ignition::math::Pose3d(initial_xyz, initial_q);
2478 std::ostringstream pose_stream;
2479 ignition::math::Vector3d model_rpy = new_model_pose.Rot().Euler();
2480 pose_stream << new_model_pose.Pos().X() <<
" " << new_model_pose.Pos().Y() <<
" " << new_model_pose.Pos().Z() <<
" "
2481 << model_rpy.X() <<
" " << model_rpy.Y() <<
" " << model_rpy.Z();
2484 TiXmlText* text =
new TiXmlText(pose_stream.str());
2485 TiXmlElement* new_pose_element =
new TiXmlElement(
"pose");
2486 new_pose_element->LinkEndChild(text);
2487 model_tixml->LinkEndChild(new_pose_element);
2493 std::vector<std::string> pieces;
2494 std::vector<double> vals;
2496 boost::split(pieces, str, boost::is_any_of(
" "));
2497 for (
unsigned int i = 0; i < pieces.size(); ++i)
2499 if (pieces[i] !=
"")
2503 vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
2505 catch(boost::bad_lexical_cast &e)
2507 sdferr <<
"xml key [" << str
2508 <<
"][" << i <<
"] value [" << pieces[i]
2509 <<
"] is not a valid double from a 3-tuple\n";
2510 return ignition::math::Pose3d();
2515 if (vals.size() == 6)
2516 return ignition::math::Pose3d(vals[0], vals[1], vals[2], vals[3], vals[4], vals[5]);
2519 ROS_ERROR_NAMED(
"api_plugin",
"Beware: failed to parse string [%s] as ignition::math::Pose3d, returning zeros.", str.c_str());
2520 return ignition::math::Pose3d();
2526 std::vector<std::string> pieces;
2527 std::vector<double> vals;
2529 boost::split(pieces, str, boost::is_any_of(
" "));
2530 for (
unsigned int i = 0; i < pieces.size(); ++i)
2532 if (pieces[i] !=
"")
2536 vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
2538 catch(boost::bad_lexical_cast &e)
2540 sdferr <<
"xml key [" << str
2541 <<
"][" << i <<
"] value [" << pieces[i]
2542 <<
"] is not a valid double from a 3-tuple\n";
2543 return ignition::math::Vector3d();
2548 if (vals.size() == 3)
2549 return ignition::math::Vector3d(vals[0], vals[1], vals[2]);
2552 ROS_ERROR_NAMED(
"api_plugin",
"Beware: failed to parse string [%s] as ignition::math::Vector3d, returning zeros.", str.c_str());
2553 return ignition::math::Vector3d();
2558 const ignition::math::Vector3d &initial_xyz,
2559 const ignition::math::Quaterniond &initial_q)
2561 TiXmlElement* model_tixml = (gazebo_model_xml.FirstChildElement(
"robot"));
2566 TiXmlElement* origin_key = model_tixml->FirstChildElement(
"origin");
2570 origin_key =
new TiXmlElement(
"origin");
2571 model_tixml->LinkEndChild(origin_key);
2574 ignition::math::Vector3d xyz;
2575 ignition::math::Vector3d rpy;
2576 if (origin_key->Attribute(
"xyz"))
2578 xyz = this->
parseVector3(origin_key->Attribute(
"xyz"));
2579 origin_key->RemoveAttribute(
"xyz");
2581 if (origin_key->Attribute(
"rpy"))
2583 rpy = this->
parseVector3(origin_key->Attribute(
"rpy"));
2584 origin_key->RemoveAttribute(
"rpy");
2588 ignition::math::Pose3d model_pose = ignition::math::Pose3d(xyz, ignition::math::Quaterniond(rpy))
2589 + ignition::math::Pose3d(initial_xyz, initial_q);
2591 std::ostringstream xyz_stream;
2592 xyz_stream << model_pose.Pos().X() <<
" " << model_pose.Pos().Y() <<
" " << model_pose.Pos().Z();
2594 std::ostringstream rpy_stream;
2595 ignition::math::Vector3d model_rpy = model_pose.Rot().Euler();
2596 rpy_stream << model_rpy.X() <<
" " << model_rpy.Y() <<
" " << model_rpy.Z();
2598 origin_key->SetAttribute(
"xyz",xyz_stream.str());
2599 origin_key->SetAttribute(
"rpy",rpy_stream.str());
2602 ROS_WARN_NAMED(
"api_plugin",
"Could not find <model> element in sdf, so name and initial position is not applied");
2607 TiXmlElement* model_tixml = gazebo_model_xml.FirstChildElement(
"robot");
2611 if (model_tixml->Attribute(
"name") != NULL)
2614 model_tixml->RemoveAttribute(
"name");
2617 model_tixml->SetAttribute(
"name",model_name);
2620 ROS_WARN_NAMED(
"api_plugin",
"Could not find <robot> element in URDF, name not replaced");
2625 TiXmlNode* child = 0;
2626 child = model_xml->IterateChildren(child);
2627 while (child != NULL)
2629 if (child->Type() == TiXmlNode::TINYXML_ELEMENT &&
2630 child->ValueStr().compare(std::string(
"plugin")) == 0)
2632 if (child->FirstChildElement(
"robotNamespace") == NULL)
2634 TiXmlElement* child_elem = child->ToElement()->FirstChildElement(
"robotNamespace");
2637 child->ToElement()->RemoveChild(child_elem);
2638 child_elem = child->ToElement()->FirstChildElement(
"robotNamespace");
2640 TiXmlElement* key =
new TiXmlElement(
"robotNamespace");
2642 key->LinkEndChild(val);
2643 child->ToElement()->LinkEndChild(key);
2647 child = model_xml->IterateChildren(child);
2652 gazebo_msgs::SpawnModel::Response &res)
2654 std::string entity_type = gazebo_model_xml.RootElement()->FirstChild()->Value();
2656 std::transform(entity_type.begin(), entity_type.end(), entity_type.begin(), ::tolower);
2658 bool isLight = (entity_type ==
"light");
2661 std::ostringstream stream;
2662 stream << gazebo_model_xml;
2663 std::string gazebo_model_xml_string = stream.str();
2664 ROS_DEBUG_NAMED(
"api_plugin.xml",
"Gazebo Model XML\n\n%s\n\n ",gazebo_model_xml_string.c_str());
2667 gazebo::msgs::Factory msg;
2668 gazebo::msgs::Init(msg,
"spawn_model");
2669 msg.set_sdf( gazebo_model_xml_string );
2675 gazebo::msgs::Request *entity_info_msg = gazebo::msgs::CreateRequest(
"entity_info", model_name);
2677 delete entity_info_msg;
2678 entity_info_msg =
nullptr;
2681 #if GAZEBO_MAJOR_VERSION >= 8
2682 gazebo::physics::ModelPtr model =
world_->ModelByName(model_name);
2683 gazebo::physics::LightPtr light =
world_->LightByName(model_name);
2685 gazebo::physics::ModelPtr model =
world_->GetModel(model_name);
2686 gazebo::physics::LightPtr light =
world_->Light(model_name);
2688 if ((isLight && light != NULL) || (model != NULL))
2690 ROS_ERROR_NAMED(
"api_plugin",
"SpawnModel: Failure - model name %s already exist.",model_name.c_str());
2691 res.success =
false;
2692 res.status_message =
"SpawnModel: Failure - entity already exists.";
2701 sdf_light.SetFromString(gazebo_model_xml_string);
2702 gazebo::msgs::Light msg = gazebo::msgs::LightFromSDF(sdf_light.Root()->GetElement(
"light"));
2703 msg.set_name(model_name);
2722 res.success =
false;
2723 res.status_message =
"SpawnModel: Entity pushed to spawn queue, but spawn service timed out waiting for entity to appear in simulation under the name " + model_name;
2729 #if GAZEBO_MAJOR_VERSION >= 8
2730 if ((isLight &&
world_->LightByName(model_name) != NULL)
2731 || (
world_->ModelByName(model_name) != NULL))
2733 if ((isLight &&
world_->Light(model_name) != NULL)
2734 || (
world_->GetModel(model_name) != NULL))
2740 <<
" for entity " << model_name <<
" to spawn");
2742 std::this_thread::sleep_for(std::chrono::microseconds(2000));
2747 res.status_message =
"SpawnModel: Successfully spawned entity";