23 #include <gazebo/common/Events.hh> 24 #include <gazebo/gazebo_config.h> 31 physics_reconfigure_initialized_(false),
32 world_created_(false),
34 plugin_loaded_(false),
35 pub_link_states_connection_count_(0),
36 pub_model_states_connection_count_(0),
37 pub_clock_frequency_(0),
38 enable_ros_network_(true)
125 ROS_ERROR_NAMED(
"api_plugin",
"Something other than this gazebo_ros_api plugin started ros::init(...), command line arguments may not be parsed properly.");
159 ROS_INFO_NAMED(
"api_plugin",
"Finished loading Gazebo ROS API Plugin.");
176 world_ = gazebo::physics::get_world(world_name);
181 ROS_FATAL_NAMED(
"api_plugin",
"cannot load gazebo ros api server plugin, physics::get_world() fails to return world");
185 gazebonode_ = gazebo::transport::NodePtr(
new gazebo::transport::Node());
203 pub_clock_ =
nh_->advertise<rosgraph_msgs::Clock>(
"/clock",10);
205 if(!(
nh_->hasParam(
"/use_sim_time")))
206 nh_->setParam(
"/use_sim_time",
true);
209 #if GAZEBO_MAJOR_VERSION >= 8 228 static const double timeout = 0.001;
239 ROS_INFO_NAMED(
"api_plugin",
"ROS gazebo topics/services are disabled");
244 pub_clock_ =
nh_->advertise<rosgraph_msgs::Clock>(
"/clock",10);
247 std::string spawn_sdf_model_service_name(
"spawn_sdf_model");
249 ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
250 spawn_sdf_model_service_name,
256 std::string spawn_urdf_model_service_name(
"spawn_urdf_model");
258 ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
259 spawn_urdf_model_service_name,
265 std::string delete_model_service_name(
"delete_model");
267 ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteModel>(
268 delete_model_service_name,
274 std::string delete_light_service_name(
"delete_light");
276 ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteLight>(
277 delete_light_service_name,
283 std::string get_model_properties_service_name(
"get_model_properties");
285 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelProperties>(
286 get_model_properties_service_name,
292 std::string get_model_state_service_name(
"get_model_state");
294 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelState>(
295 get_model_state_service_name,
301 std::string get_world_properties_service_name(
"get_world_properties");
303 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetWorldProperties>(
304 get_world_properties_service_name,
310 std::string get_joint_properties_service_name(
"get_joint_properties");
312 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetJointProperties>(
313 get_joint_properties_service_name,
319 std::string get_link_properties_service_name(
"get_link_properties");
321 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkProperties>(
322 get_link_properties_service_name,
328 std::string get_link_state_service_name(
"get_link_state");
330 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkState>(
331 get_link_state_service_name,
337 std::string get_light_properties_service_name(
"get_light_properties");
339 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLightProperties>(
340 get_light_properties_service_name,
346 std::string set_light_properties_service_name(
"set_light_properties");
348 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLightProperties>(
349 set_light_properties_service_name,
355 std::string get_physics_properties_service_name(
"get_physics_properties");
357 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetPhysicsProperties>(
358 get_physics_properties_service_name,
365 ros::AdvertiseOptions::create<gazebo_msgs::LinkStates>(
374 ros::AdvertiseOptions::create<gazebo_msgs::ModelStates>(
382 std::string set_link_properties_service_name(
"set_link_properties");
384 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkProperties>(
385 set_link_properties_service_name,
391 std::string set_physics_properties_service_name(
"set_physics_properties");
393 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetPhysicsProperties>(
394 set_physics_properties_service_name,
400 std::string set_model_state_service_name(
"set_model_state");
402 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelState>(
403 set_model_state_service_name,
409 std::string set_model_configuration_service_name(
"set_model_configuration");
411 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelConfiguration>(
412 set_model_configuration_service_name,
418 std::string set_joint_properties_service_name(
"set_joint_properties");
420 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointProperties>(
421 set_joint_properties_service_name,
427 std::string set_link_state_service_name(
"set_link_state");
429 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkState>(
430 set_link_state_service_name,
438 ros::SubscribeOptions::create<gazebo_msgs::LinkState>(
446 ros::SubscribeOptions::create<gazebo_msgs::ModelState>(
447 "set_model_state",10,
453 std::string pause_physics_service_name(
"pause_physics");
455 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
456 pause_physics_service_name,
462 std::string unpause_physics_service_name(
"unpause_physics");
464 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
465 unpause_physics_service_name,
471 std::string apply_body_wrench_service_name(
"apply_body_wrench");
473 ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyBodyWrench>(
474 apply_body_wrench_service_name,
480 std::string apply_joint_effort_service_name(
"apply_joint_effort");
482 ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyJointEffort>(
483 apply_joint_effort_service_name,
489 std::string clear_joint_forces_service_name(
"clear_joint_forces");
491 ros::AdvertiseServiceOptions::create<gazebo_msgs::JointRequest>(
492 clear_joint_forces_service_name,
498 std::string clear_body_wrenches_service_name(
"clear_body_wrenches");
500 ros::AdvertiseServiceOptions::create<gazebo_msgs::BodyRequest>(
501 clear_body_wrenches_service_name,
507 std::string reset_simulation_service_name(
"reset_simulation");
509 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
510 reset_simulation_service_name,
516 std::string reset_world_service_name(
"reset_world");
518 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
519 reset_world_service_name,
526 if(!(
nh_->hasParam(
"/use_sim_time")))
527 nh_->setParam(
"/use_sim_time",
true);
531 #if GAZEBO_MAJOR_VERSION >= 8 559 ROS_ERROR_NAMED(
"api_plugin",
"One too mandy disconnect from pub_link_states_ in gazebo_ros.cpp? something weird");
570 ROS_ERROR_NAMED(
"api_plugin",
"One too mandy disconnect from pub_model_states_ in gazebo_ros.cpp? something weird");
575 gazebo_msgs::SpawnModel::Response &res)
581 std::string model_xml = req.model_xml;
585 ROS_ERROR_NAMED(
"api_plugin",
"SpawnModel: Failure - entity format is invalid.");
587 res.status_message =
"SpawnModel: Failure - entity format is invalid.";
595 std::string open_bracket(
"<?");
596 std::string close_bracket(
"?>");
597 size_t pos1 = model_xml.find(open_bracket,0);
598 size_t pos2 = model_xml.find(close_bracket,0);
599 if (pos1 != std::string::npos && pos2 != std::string::npos)
600 model_xml.replace(pos1,pos2-pos1+2,std::string(
""));
605 std::string open_comment(
"<!--");
606 std::string close_comment(
"-->");
608 while((pos1 = model_xml.find(open_comment,0)) != std::string::npos){
609 size_t pos2 = model_xml.find(close_comment,0);
610 if (pos2 != std::string::npos)
611 model_xml.replace(pos1,pos2-pos1+3,std::string(
""));
617 std::string package_prefix(
"package://");
618 size_t pos1 = model_xml.find(package_prefix,0);
619 while (pos1 != std::string::npos)
621 size_t pos2 = model_xml.find(
"/", pos1+10);
623 if (pos2 == std::string::npos || pos1 >= pos2)
629 std::string package_name = model_xml.substr(pos1+10,pos2-pos1-10);
632 if (package_path.empty())
634 ROS_FATAL_NAMED(
"api_plugin",
"Package[%s] does not have a path",package_name.c_str());
636 res.status_message =
"urdf reference package name does not exist: " + package_name;
639 ROS_DEBUG_ONCE_NAMED(
"api_plugin",
"Package name [%s] has path [%s]", package_name.c_str(), package_path.c_str());
641 model_xml.replace(pos1,(pos2-pos1),package_path);
642 pos1 = model_xml.find(package_prefix, pos1);
647 req.model_xml = model_xml;
654 gazebo_msgs::SpawnModel::Response &res)
657 std::string model_name = req.model_name;
663 ignition::math::Vector3d initial_xyz(req.initial_pose.position.x,req.initial_pose.position.y,req.initial_pose.position.z);
665 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);
668 #if GAZEBO_MAJOR_VERSION >= 8 669 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
671 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
676 #if GAZEBO_MAJOR_VERSION >= 8 677 ignition::math::Pose3d frame_pose = frame->WorldPose();
679 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
681 initial_xyz = frame_pose.Pos() + frame_pose.Rot().RotateVector(initial_xyz);
682 initial_q = frame_pose.Rot() * initial_q;
686 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
688 ROS_DEBUG_NAMED(
"api_plugin",
"SpawnModel: reference_frame is empty/world/map, using inertial frame");
693 res.status_message =
"SpawnModel: reference reference_frame not found, did you forget to scope the link by model name?";
698 std::string model_xml = req.model_xml;
706 TiXmlDocument gazebo_model_xml;
707 gazebo_model_xml.Parse(model_xml.c_str());
710 if (
isSDF(model_xml))
720 TiXmlNode* model_tixml = gazebo_model_xml.FirstChild(
"sdf");
721 model_tixml = (!model_tixml) ?
722 gazebo_model_xml.FirstChild(
"gazebo") : model_tixml;
729 ROS_WARN_NAMED(
"api_plugin",
"Unable to add robot namespace to xml");
733 else if (
isURDF(model_xml))
743 TiXmlNode* model_tixml = gazebo_model_xml.FirstChild(
"robot");
750 ROS_WARN_NAMED(
"api_plugin",
"Unable to add robot namespace to xml");
756 ROS_ERROR_NAMED(
"api_plugin",
"GazeboRosApiPlugin SpawnModel Failure: input xml format not recognized");
758 res.status_message =
"GazeboRosApiPlugin SpawnModel Failure: input model_xml not SDF or URDF, or cannot be converted to Gazebo compatible format.";
767 gazebo_msgs::DeleteModel::Response &res)
770 #if GAZEBO_MAJOR_VERSION >= 8 771 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
773 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
777 ROS_ERROR_NAMED(
"api_plugin",
"DeleteModel: model [%s] does not exist",req.model_name.c_str());
779 res.status_message =
"DeleteModel: model does not exist";
784 for (
unsigned int i = 0 ; i < model->GetChildCount(); i ++)
786 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
795 gazebo::physics::Joint_V joints = model->GetJoints();
796 for (
unsigned int i=0;i< joints.size(); i++)
803 gazebo::msgs::Request *msg = gazebo::msgs::CreateRequest(
"entity_delete",req.model_name);
814 res.status_message =
"DeleteModel: Model pushed to delete queue, but delete service timed out waiting for model to disappear from simulation";
819 #if GAZEBO_MAJOR_VERSION >= 8 820 if (!
world_->ModelByName(req.model_name))
break;
822 if (!
world_->GetModel(req.model_name))
break;
825 ROS_DEBUG_NAMED(
"api_plugin",
"Waiting for model deletion (%s)",req.model_name.c_str());
831 res.status_message =
"DeleteModel: successfully deleted model";
836 gazebo_msgs::DeleteLight::Response &res)
838 #if GAZEBO_MAJOR_VERSION >= 8 839 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
841 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
844 if (phy_light == NULL)
847 res.status_message =
"DeleteLight: Requested light " + req.light_name +
" not found!";
851 gazebo::msgs::Request* msg = gazebo::msgs::CreateRequest(
"entity_delete", req.light_name);
856 for (
int i = 0; i < 100; i++)
858 #if GAZEBO_MAJOR_VERSION >= 8 859 phy_light =
world_->LightByName(req.light_name);
861 phy_light =
world_->Light(req.light_name);
863 if (phy_light == NULL)
866 res.status_message =
"DeleteLight: " + req.light_name +
" successfully deleted";
874 res.status_message =
"DeleteLight: Timeout reached while removing light \"" + req.light_name
881 gazebo_msgs::GetModelState::Response &res)
883 #if GAZEBO_MAJOR_VERSION >= 8 884 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
885 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.relative_entity_name);
887 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
888 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.relative_entity_name);
892 ROS_ERROR_NAMED(
"api_plugin",
"GetModelState: model [%s] does not exist",req.model_name.c_str());
894 res.status_message =
"GetModelState: model does not exist";
914 res.header.seq = it->second;
917 res.header.frame_id = req.relative_entity_name;
921 #if GAZEBO_MAJOR_VERSION >= 8 922 ignition::math::Pose3d model_pose = model->WorldPose();
923 ignition::math::Vector3d model_linear_vel = model->WorldLinearVel();
924 ignition::math::Vector3d model_angular_vel = model->WorldAngularVel();
926 ignition::math::Pose3d model_pose = model->GetWorldPose().Ign();
927 ignition::math::Vector3d model_linear_vel = model->GetWorldLinearVel().Ign();
928 ignition::math::Vector3d model_angular_vel = model->GetWorldAngularVel().Ign();
930 ignition::math::Vector3d model_pos = model_pose.Pos();
931 ignition::math::Quaterniond model_rot = model_pose.Rot();
938 #if GAZEBO_MAJOR_VERSION >= 8 939 ignition::math::Pose3d frame_pose = frame->WorldPose();
940 ignition::math::Vector3d frame_vpos = frame->WorldLinearVel();
941 ignition::math::Vector3d frame_veul = frame->WorldAngularVel();
943 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
944 ignition::math::Vector3d frame_vpos = frame->GetWorldLinearVel().Ign();
945 ignition::math::Vector3d frame_veul = frame->GetWorldAngularVel().Ign();
947 ignition::math::Pose3d model_rel_pose = model_pose - frame_pose;
948 model_pos = model_rel_pose.Pos();
949 model_rot = model_rel_pose.Rot();
951 model_linear_vel = frame_pose.Rot().RotateVectorReverse(model_linear_vel - frame_vpos);
952 model_angular_vel = frame_pose.Rot().RotateVectorReverse(model_angular_vel - frame_veul);
955 else if (req.relative_entity_name ==
"" || req.relative_entity_name ==
"world" || req.relative_entity_name ==
"map" || req.relative_entity_name ==
"/map")
957 ROS_DEBUG_NAMED(
"api_plugin",
"GetModelState: relative_entity_name is empty/world/map, using inertial frame");
962 res.status_message =
"GetModelState: reference relative_entity_name not found, did you forget to scope the body by model name?";
967 res.pose.position.x = model_pos.X();
968 res.pose.position.y = model_pos.Y();
969 res.pose.position.z = model_pos.Z();
970 res.pose.orientation.w = model_rot.W();
971 res.pose.orientation.x = model_rot.X();
972 res.pose.orientation.y = model_rot.Y();
973 res.pose.orientation.z = model_rot.Z();
975 res.twist.linear.x = model_linear_vel.X();
976 res.twist.linear.y = model_linear_vel.Y();
977 res.twist.linear.z = model_linear_vel.Z();
978 res.twist.angular.x = model_angular_vel.X();
979 res.twist.angular.y = model_angular_vel.Y();
980 res.twist.angular.z = model_angular_vel.Z();
983 res.status_message =
"GetModelState: got properties";
990 gazebo_msgs::GetModelProperties::Response &res)
992 #if GAZEBO_MAJOR_VERSION >= 8 993 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
995 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
999 ROS_ERROR_NAMED(
"api_plugin",
"GetModelProperties: model [%s] does not exist",req.model_name.c_str());
1000 res.success =
false;
1001 res.status_message =
"GetModelProperties: model does not exist";
1007 gazebo::physics::ModelPtr parent_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetParent());
1008 if (parent_model) res.parent_model_name = parent_model->GetName();
1011 res.body_names.clear();
1012 res.geom_names.clear();
1013 for (
unsigned int i = 0 ; i < model->GetChildCount(); i ++)
1015 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
1018 res.body_names.push_back(body->GetName());
1020 for (
unsigned int j = 0; j < body->GetChildCount() ; j++)
1022 gazebo::physics::CollisionPtr geom = boost::dynamic_pointer_cast<gazebo::physics::Collision>(body->GetChild(j));
1024 res.geom_names.push_back(geom->GetName());
1030 res.joint_names.clear();
1032 gazebo::physics::Joint_V joints = model->GetJoints();
1033 for (
unsigned int i=0;i< joints.size(); i++)
1034 res.joint_names.push_back( joints[i]->GetName() );
1037 res.child_model_names.clear();
1038 for (
unsigned int j = 0; j < model->GetChildCount(); j++)
1040 gazebo::physics::ModelPtr child_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetChild(j));
1042 res.child_model_names.push_back(child_model->GetName() );
1046 res.is_static = model->IsStatic();
1049 res.status_message =
"GetModelProperties: got properties";
1056 gazebo_msgs::GetWorldProperties::Response &res)
1058 res.model_names.clear();
1059 #if GAZEBO_MAJOR_VERSION >= 8 1060 res.sim_time =
world_->SimTime().Double();
1061 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1062 res.model_names.push_back(
world_->ModelByIndex(i)->GetName());
1064 res.sim_time =
world_->GetSimTime().Double();
1065 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1066 res.model_names.push_back(
world_->GetModel(i)->GetName());
1068 gzerr <<
"disablign rendering has not been implemented, rendering is always enabled\n";
1069 res.rendering_enabled =
true;
1071 res.status_message =
"GetWorldProperties: got properties";
1076 gazebo_msgs::GetJointProperties::Response &res)
1078 gazebo::physics::JointPtr joint;
1079 #if GAZEBO_MAJOR_VERSION >= 8 1080 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1082 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1084 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1086 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1093 res.success =
false;
1094 res.status_message =
"GetJointProperties: joint not found";
1100 res.type = res.REVOLUTE;
1102 res.damping.clear();
1105 res.position.clear();
1106 #if GAZEBO_MAJOR_VERSION >= 8 1107 res.position.push_back(joint->Position(0));
1109 res.position.push_back(joint->GetAngle(0).Radian());
1113 res.rate.push_back(joint->GetVelocity(0));
1116 res.status_message =
"GetJointProperties: got properties";
1122 gazebo_msgs::GetLinkProperties::Response &res)
1124 #if GAZEBO_MAJOR_VERSION >= 8 1125 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1127 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1131 res.success =
false;
1132 res.status_message =
"GetLinkProperties: link not found, did you forget to scope the link by model name?";
1138 res.gravity_mode = body->GetGravityMode();
1140 gazebo::physics::InertialPtr inertia = body->GetInertial();
1142 #if GAZEBO_MAJOR_VERSION >= 8 1143 res.mass = body->GetInertial()->Mass();
1145 res.ixx = inertia->IXX();
1146 res.iyy = inertia->IYY();
1147 res.izz = inertia->IZZ();
1148 res.ixy = inertia->IXY();
1149 res.ixz = inertia->IXZ();
1150 res.iyz = inertia->IYZ();
1152 ignition::math::Vector3d com = body->GetInertial()->CoG();
1154 res.mass = body->GetInertial()->GetMass();
1156 res.ixx = inertia->GetIXX();
1157 res.iyy = inertia->GetIYY();
1158 res.izz = inertia->GetIZZ();
1159 res.ixy = inertia->GetIXY();
1160 res.ixz = inertia->GetIXZ();
1161 res.iyz = inertia->GetIYZ();
1163 ignition::math::Vector3d com = body->GetInertial()->GetCoG().Ign();
1165 res.com.position.x = com.X();
1166 res.com.position.y = com.Y();
1167 res.com.position.z = com.Z();
1168 res.com.orientation.x = 0;
1169 res.com.orientation.y = 0;
1170 res.com.orientation.z = 0;
1171 res.com.orientation.w = 1;
1174 res.status_message =
"GetLinkProperties: got properties";
1180 gazebo_msgs::GetLinkState::Response &res)
1182 #if GAZEBO_MAJOR_VERSION >= 8 1183 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1184 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
1186 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1187 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
1192 res.success =
false;
1193 res.status_message =
"GetLinkState: link not found, did you forget to scope the link by model name?";
1199 #if GAZEBO_MAJOR_VERSION >= 8 1200 ignition::math::Pose3d body_pose = body->WorldPose();
1201 ignition::math::Vector3d body_vpos = body->WorldLinearVel();
1202 ignition::math::Vector3d body_veul = body->WorldAngularVel();
1204 ignition::math::Pose3d body_pose = body->GetWorldPose().Ign();
1205 ignition::math::Vector3d body_vpos = body->GetWorldLinearVel().Ign();
1206 ignition::math::Vector3d body_veul = body->GetWorldAngularVel().Ign();
1212 #if GAZEBO_MAJOR_VERSION >= 8 1213 ignition::math::Pose3d frame_pose = frame->WorldPose();
1214 ignition::math::Vector3d frame_vpos = frame->WorldLinearVel();
1215 ignition::math::Vector3d frame_veul = frame->WorldAngularVel();
1217 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
1218 ignition::math::Vector3d frame_vpos = frame->GetWorldLinearVel().Ign();
1219 ignition::math::Vector3d frame_veul = frame->GetWorldAngularVel().Ign();
1221 body_pose = body_pose - frame_pose;
1223 body_vpos = frame_pose.Rot().RotateVectorReverse(body_vpos - frame_vpos);
1224 body_veul = frame_pose.Rot().RotateVectorReverse(body_veul - frame_veul);
1227 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
1229 ROS_DEBUG_NAMED(
"api_plugin",
"GetLinkState: reference_frame is empty/world/map, using inertial frame");
1233 res.success =
false;
1234 res.status_message =
"GetLinkState: reference reference_frame not found, did you forget to scope the link by model name?";
1238 res.link_state.link_name = req.link_name;
1239 res.link_state.pose.position.x = body_pose.Pos().X();
1240 res.link_state.pose.position.y = body_pose.Pos().Y();
1241 res.link_state.pose.position.z = body_pose.Pos().Z();
1242 res.link_state.pose.orientation.x = body_pose.Rot().X();
1243 res.link_state.pose.orientation.y = body_pose.Rot().Y();
1244 res.link_state.pose.orientation.z = body_pose.Rot().Z();
1245 res.link_state.pose.orientation.w = body_pose.Rot().W();
1246 res.link_state.twist.linear.x = body_vpos.X();
1247 res.link_state.twist.linear.y = body_vpos.Y();
1248 res.link_state.twist.linear.z = body_vpos.Z();
1249 res.link_state.twist.angular.x = body_veul.X();
1250 res.link_state.twist.angular.y = body_veul.Y();
1251 res.link_state.twist.angular.z = body_veul.Z();
1252 res.link_state.reference_frame = req.reference_frame;
1255 res.status_message =
"GetLinkState: got state";
1260 gazebo_msgs::GetLightProperties::Response &res)
1262 #if GAZEBO_MAJOR_VERSION >= 8 1263 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
1265 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
1268 if (phy_light == NULL)
1270 res.success =
false;
1271 res.status_message =
"getLightProperties: Requested light " + req.light_name +
" not found!";
1275 gazebo::msgs::Light light;
1276 phy_light->FillMsg(light);
1278 res.diffuse.r = light.diffuse().r();
1279 res.diffuse.g = light.diffuse().g();
1280 res.diffuse.b = light.diffuse().b();
1281 res.diffuse.a = light.diffuse().a();
1283 res.attenuation_constant = light.attenuation_constant();
1284 res.attenuation_linear = light.attenuation_linear();
1285 res.attenuation_quadratic = light.attenuation_quadratic();
1294 gazebo_msgs::SetLightProperties::Response &res)
1296 #if GAZEBO_MAJOR_VERSION >= 8 1297 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
1299 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
1302 if (phy_light == NULL)
1304 res.success =
false;
1305 res.status_message =
"setLightProperties: Requested light " + req.light_name +
" not found!";
1309 gazebo::msgs::Light light;
1311 phy_light->FillMsg(light);
1313 light.mutable_diffuse()->set_r(req.diffuse.r);
1314 light.mutable_diffuse()->set_g(req.diffuse.g);
1315 light.mutable_diffuse()->set_b(req.diffuse.b);
1316 light.mutable_diffuse()->set_a(req.diffuse.a);
1318 light.set_attenuation_constant(req.attenuation_constant);
1319 light.set_attenuation_linear(req.attenuation_linear);
1320 light.set_attenuation_quadratic(req.attenuation_quadratic);
1331 gazebo_msgs::SetLinkProperties::Response &res)
1333 #if GAZEBO_MAJOR_VERSION >= 8 1334 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1336 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1340 res.success =
false;
1341 res.status_message =
"SetLinkProperties: link not found, did you forget to scope the link by model name?";
1346 gazebo::physics::InertialPtr mass = body->GetInertial();
1349 mass->SetCoG(ignition::math::Vector3d(req.com.position.x,req.com.position.y,req.com.position.z));
1350 mass->SetInertiaMatrix(req.ixx,req.iyy,req.izz,req.ixy,req.ixz,req.iyz);
1351 mass->SetMass(req.mass);
1352 body->SetGravityMode(req.gravity_mode);
1355 res.status_message =
"SetLinkProperties: properties set";
1361 gazebo_msgs::SetPhysicsProperties::Response &res)
1364 bool is_paused =
world_->IsPaused();
1366 world_->SetGravity(ignition::math::Vector3d(req.gravity.x,req.gravity.y,req.gravity.z));
1369 #if GAZEBO_MAJOR_VERSION >= 8 1370 gazebo::physics::PhysicsEnginePtr pe = (
world_->Physics());
1372 gazebo::physics::PhysicsEnginePtr pe = (
world_->GetPhysicsEngine());
1374 pe->SetMaxStepSize(req.time_step);
1375 pe->SetRealTimeUpdateRate(req.max_update_rate);
1377 if (pe->GetType() ==
"ode")
1380 pe->SetAutoDisableFlag(req.ode_config.auto_disable_bodies);
1381 pe->SetParam(
"precon_iters",
int(req.ode_config.sor_pgs_precon_iters));
1382 pe->SetParam(
"iters",
int(req.ode_config.sor_pgs_iters));
1383 pe->SetParam(
"sor", req.ode_config.sor_pgs_w);
1384 pe->SetParam(
"cfm", req.ode_config.cfm);
1385 pe->SetParam(
"erp", req.ode_config.erp);
1386 pe->SetParam(
"contact_surface_layer",
1387 req.ode_config.contact_surface_layer);
1388 pe->SetParam(
"contact_max_correcting_vel",
1389 req.ode_config.contact_max_correcting_vel);
1390 pe->SetParam(
"max_contacts",
int(req.ode_config.max_contacts));
1392 world_->SetPaused(is_paused);
1395 res.status_message =
"physics engine updated";
1400 ROS_ERROR_NAMED(
"api_plugin",
"ROS set_physics_properties service call does not yet support physics engine [%s].", pe->GetType().c_str());
1401 res.success =
false;
1402 res.status_message =
"Physics engine [" + pe->GetType() +
"]: set_physics_properties not supported.";
1408 gazebo_msgs::GetPhysicsProperties::Response &res)
1411 #if GAZEBO_MAJOR_VERSION >= 8 1412 gazebo::physics::PhysicsEnginePtr pe = (
world_->Physics());
1414 gazebo::physics::PhysicsEnginePtr pe = (
world_->GetPhysicsEngine());
1416 res.time_step = pe->GetMaxStepSize();
1417 res.pause =
world_->IsPaused();
1418 res.max_update_rate = pe->GetRealTimeUpdateRate();
1419 ignition::math::Vector3d gravity =
world_->Gravity();
1420 res.gravity.x = gravity.X();
1421 res.gravity.y = gravity.Y();
1422 res.gravity.z = gravity.Z();
1425 if (pe->GetType() ==
"ode")
1427 res.ode_config.auto_disable_bodies =
1428 pe->GetAutoDisableFlag();
1429 res.ode_config.sor_pgs_precon_iters = boost::any_cast<
int>(
1430 pe->GetParam(
"precon_iters"));
1431 res.ode_config.sor_pgs_iters = boost::any_cast<
int>(
1432 pe->GetParam(
"iters"));
1433 res.ode_config.sor_pgs_w = boost::any_cast<
double>(
1434 pe->GetParam(
"sor"));
1435 res.ode_config.contact_surface_layer = boost::any_cast<
double>(
1436 pe->GetParam(
"contact_surface_layer"));
1437 res.ode_config.contact_max_correcting_vel = boost::any_cast<
double>(
1438 pe->GetParam(
"contact_max_correcting_vel"));
1439 res.ode_config.cfm = boost::any_cast<
double>(
1440 pe->GetParam(
"cfm"));
1441 res.ode_config.erp = boost::any_cast<
double>(
1442 pe->GetParam(
"erp"));
1443 res.ode_config.max_contacts = boost::any_cast<
int>(
1444 pe->GetParam(
"max_contacts"));
1447 res.status_message =
"GetPhysicsProperties: got properties";
1452 ROS_ERROR_NAMED(
"api_plugin",
"ROS get_physics_properties service call does not yet support physics engine [%s].", pe->GetType().c_str());
1453 res.success =
false;
1454 res.status_message =
"Physics engine [" + pe->GetType() +
"]: get_physics_properties not supported.";
1460 gazebo_msgs::SetJointProperties::Response &res)
1463 gazebo::physics::JointPtr joint;
1464 #if GAZEBO_MAJOR_VERSION >= 8 1465 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1467 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1469 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1471 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1478 res.success =
false;
1479 res.status_message =
"SetJointProperties: joint not found";
1484 for(
unsigned int i=0;i< req.ode_joint_config.damping.size();i++)
1485 joint->SetDamping(i,req.ode_joint_config.damping[i]);
1486 for(
unsigned int i=0;i< req.ode_joint_config.hiStop.size();i++)
1487 joint->SetParam(
"hi_stop",i,req.ode_joint_config.hiStop[i]);
1488 for(
unsigned int i=0;i< req.ode_joint_config.loStop.size();i++)
1489 joint->SetParam(
"lo_stop",i,req.ode_joint_config.loStop[i]);
1490 for(
unsigned int i=0;i< req.ode_joint_config.erp.size();i++)
1491 joint->SetParam(
"erp",i,req.ode_joint_config.erp[i]);
1492 for(
unsigned int i=0;i< req.ode_joint_config.cfm.size();i++)
1493 joint->SetParam(
"cfm",i,req.ode_joint_config.cfm[i]);
1494 for(
unsigned int i=0;i< req.ode_joint_config.stop_erp.size();i++)
1495 joint->SetParam(
"stop_erp",i,req.ode_joint_config.stop_erp[i]);
1496 for(
unsigned int i=0;i< req.ode_joint_config.stop_cfm.size();i++)
1497 joint->SetParam(
"stop_cfm",i,req.ode_joint_config.stop_cfm[i]);
1498 for(
unsigned int i=0;i< req.ode_joint_config.fudge_factor.size();i++)
1499 joint->SetParam(
"fudge_factor",i,req.ode_joint_config.fudge_factor[i]);
1500 for(
unsigned int i=0;i< req.ode_joint_config.fmax.size();i++)
1501 joint->SetParam(
"fmax",i,req.ode_joint_config.fmax[i]);
1502 for(
unsigned int i=0;i< req.ode_joint_config.vel.size();i++)
1503 joint->SetParam(
"vel",i,req.ode_joint_config.vel[i]);
1506 res.status_message =
"SetJointProperties: properties set";
1512 gazebo_msgs::SetModelState::Response &res)
1514 ignition::math::Vector3d target_pos(req.model_state.pose.position.x,req.model_state.pose.position.y,req.model_state.pose.position.z);
1515 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);
1516 target_rot.Normalize();
1517 ignition::math::Pose3d target_pose(target_pos,target_rot);
1518 ignition::math::Vector3d target_pos_dot(req.model_state.twist.linear.x,req.model_state.twist.linear.y,req.model_state.twist.linear.z);
1519 ignition::math::Vector3d target_rot_dot(req.model_state.twist.angular.x,req.model_state.twist.angular.y,req.model_state.twist.angular.z);
1521 #if GAZEBO_MAJOR_VERSION >= 8 1522 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_state.model_name);
1524 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_state.model_name);
1528 ROS_ERROR_NAMED(
"api_plugin",
"Updating ModelState: model [%s] does not exist",req.model_state.model_name.c_str());
1529 res.success =
false;
1530 res.status_message =
"SetModelState: model does not exist";
1535 #if GAZEBO_MAJOR_VERSION >= 8 1536 gazebo::physics::EntityPtr relative_entity =
world_->EntityByName(req.model_state.reference_frame);
1538 gazebo::physics::EntityPtr relative_entity =
world_->GetEntity(req.model_state.reference_frame);
1540 if (relative_entity)
1542 #if GAZEBO_MAJOR_VERSION >= 8 1543 ignition::math::Pose3d frame_pose = relative_entity->WorldPose();
1545 ignition::math::Pose3d frame_pose = relative_entity->GetWorldPose().Ign();
1548 target_pose = target_pose + frame_pose;
1552 target_pos_dot = frame_pose.Rot().RotateVector(target_pos_dot);
1553 target_rot_dot = frame_pose.Rot().RotateVector(target_rot_dot);
1556 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" )
1558 ROS_DEBUG_NAMED(
"api_plugin",
"Updating ModelState: reference frame is empty/world/map, usig inertial frame");
1562 ROS_ERROR_NAMED(
"api_plugin",
"Updating ModelState: for model[%s], specified reference frame entity [%s] does not exist",
1563 req.model_state.model_name.c_str(),req.model_state.reference_frame.c_str());
1564 res.success =
false;
1565 res.status_message =
"SetModelState: specified reference frame entity does not exist";
1570 bool is_paused =
world_->IsPaused();
1572 model->SetWorldPose(target_pose);
1573 world_->SetPaused(is_paused);
1574 #if GAZEBO_MAJOR_VERSION >= 8 1582 model->SetLinearVel(target_pos_dot);
1583 model->SetAngularVel(target_rot_dot);
1586 res.status_message =
"SetModelState: set model state done";
1593 gazebo_msgs::SetModelState::Response res;
1594 gazebo_msgs::SetModelState::Request req;
1595 req.model_state = *model_state;
1600 gazebo_msgs::ApplyJointEffort::Response &res)
1602 gazebo::physics::JointPtr joint;
1603 #if GAZEBO_MAJOR_VERSION >= 8 1604 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1606 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1608 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1610 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1616 fjj->
force = req.effort;
1618 #if GAZEBO_MAJOR_VERSION >= 8 1631 res.status_message =
"ApplyJointEffort: effort set";
1636 res.success =
false;
1637 res.status_message =
"ApplyJointEffort: joint not found";
1649 world_->ResetEntities(gazebo::physics::Base::MODEL);
1661 world_->SetPaused(
false);
1666 gazebo_msgs::JointRequest::Response &res)
1679 if ((*iter)->joint->GetName() == joint_name)
1694 gazebo_msgs::BodyRequest::Response &res)
1708 if ((*iter)->body->GetScopedName() == body_name)
1723 gazebo_msgs::SetModelConfiguration::Response &res)
1725 std::string gazebo_model_name = req.model_name;
1728 #if GAZEBO_MAJOR_VERSION >= 8 1729 gazebo::physics::ModelPtr gazebo_model =
world_->ModelByName(req.model_name);
1731 gazebo::physics::ModelPtr gazebo_model =
world_->GetModel(req.model_name);
1735 ROS_ERROR_NAMED(
"api_plugin",
"SetModelConfiguration: model [%s] does not exist",gazebo_model_name.c_str());
1736 res.success =
false;
1737 res.status_message =
"SetModelConfiguration: model does not exist";
1741 if (req.joint_names.size() == req.joint_positions.size())
1743 std::map<std::string, double> joint_position_map;
1744 for (
unsigned int i = 0; i < req.joint_names.size(); i++)
1746 joint_position_map[req.joint_names[i]] = req.joint_positions[i];
1750 bool is_paused =
world_->IsPaused();
1751 if (!is_paused)
world_->SetPaused(
true);
1753 gazebo_model->SetJointPositions(joint_position_map);
1756 world_->SetPaused(is_paused);
1759 res.status_message =
"SetModelConfiguration: success";
1764 res.success =
false;
1765 res.status_message =
"SetModelConfiguration: joint name and position list have different lengths";
1771 gazebo_msgs::SetLinkState::Response &res)
1773 #if GAZEBO_MAJOR_VERSION >= 8 1774 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_state.link_name));
1775 gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_state.reference_frame));
1777 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_state.link_name));
1778 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.link_state.reference_frame);
1782 ROS_ERROR_NAMED(
"api_plugin",
"Updating LinkState: link [%s] does not exist",req.link_state.link_name.c_str());
1783 res.success =
false;
1784 res.status_message =
"SetLinkState: link does not exist";
1791 ignition::math::Vector3d target_pos(req.link_state.pose.position.x,req.link_state.pose.position.y,req.link_state.pose.position.z);
1792 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);
1793 ignition::math::Pose3d target_pose(target_pos,target_rot);
1794 ignition::math::Vector3d target_linear_vel(req.link_state.twist.linear.x,req.link_state.twist.linear.y,req.link_state.twist.linear.z);
1795 ignition::math::Vector3d target_angular_vel(req.link_state.twist.angular.x,req.link_state.twist.angular.y,req.link_state.twist.angular.z);
1799 #if GAZEBO_MAJOR_VERSION >= 8 1800 ignition::math::Pose3d frame_pose = frame->WorldPose();
1801 ignition::math::Vector3d frame_linear_vel = frame->WorldLinearVel();
1802 ignition::math::Vector3d frame_angular_vel = frame->WorldAngularVel();
1804 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
1805 ignition::math::Vector3d frame_linear_vel = frame->GetWorldLinearVel().Ign();
1806 ignition::math::Vector3d frame_angular_vel = frame->GetWorldAngularVel().Ign();
1808 ignition::math::Vector3d frame_pos = frame_pose.Pos();
1809 ignition::math::Quaterniond frame_rot = frame_pose.Rot();
1812 target_pose = target_pose + frame_pose;
1814 target_linear_vel -= frame_linear_vel;
1815 target_angular_vel -= frame_angular_vel;
1817 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")
1819 ROS_INFO_NAMED(
"api_plugin",
"Updating LinkState: reference_frame is empty/world/map, using inertial frame");
1823 ROS_ERROR_NAMED(
"api_plugin",
"Updating LinkState: reference_frame is not a valid entity name");
1824 res.success =
false;
1825 res.status_message =
"SetLinkState: failed";
1832 bool is_paused =
world_->IsPaused();
1833 if (!is_paused)
world_->SetPaused(
true);
1834 body->SetWorldPose(target_pose);
1835 world_->SetPaused(is_paused);
1838 body->SetLinearVel(target_linear_vel);
1839 body->SetAngularVel(target_angular_vel);
1842 res.status_message =
"SetLinkState: success";
1848 gazebo_msgs::SetLinkState::Request req;
1849 gazebo_msgs::SetLinkState::Response res;
1850 req.link_state = *link_state;
1855 const ignition::math::Vector3d &reference_force,
1856 const ignition::math::Vector3d &reference_torque,
1857 const ignition::math::Pose3d &target_to_reference )
1860 target_force = target_to_reference.Rot().RotateVector(reference_force);
1862 target_torque = target_to_reference.Rot().RotateVector(reference_torque);
1865 target_torque = target_torque + target_to_reference.Pos().Cross(target_force);
1869 gazebo_msgs::ApplyBodyWrench::Response &res)
1871 #if GAZEBO_MAJOR_VERSION >= 8 1872 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.body_name));
1873 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
1875 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.body_name));
1876 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
1880 ROS_ERROR_NAMED(
"api_plugin",
"ApplyBodyWrench: body [%s] does not exist",req.body_name.c_str());
1881 res.success =
false;
1882 res.status_message =
"ApplyBodyWrench: body does not exist";
1887 ignition::math::Vector3d reference_force(req.wrench.force.x,req.wrench.force.y,req.wrench.force.z);
1888 ignition::math::Vector3d reference_torque(req.wrench.torque.x,req.wrench.torque.y,req.wrench.torque.z);
1889 ignition::math::Vector3d reference_point(req.reference_point.x,req.reference_point.y,req.reference_point.z);
1891 ignition::math::Vector3d target_force;
1892 ignition::math::Vector3d target_torque;
1896 reference_torque = reference_torque + reference_point.Cross(reference_force);
1907 #if GAZEBO_MAJOR_VERSION >= 8 1908 ignition::math::Pose3d framePose = frame->WorldPose();
1909 ignition::math::Pose3d bodyPose = body->WorldPose();
1911 ignition::math::Pose3d framePose = frame->GetWorldPose().Ign();
1912 ignition::math::Pose3d bodyPose = body->GetWorldPose().Ign();
1914 ignition::math::Pose3d target_to_reference = framePose - bodyPose;
1915 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]",
1919 bodyPose.Rot().Euler().X(),
1920 bodyPose.Rot().Euler().Y(),
1921 bodyPose.Rot().Euler().Z(),
1922 framePose.Pos().X(),
1923 framePose.Pos().Y(),
1924 framePose.Pos().Z(),
1925 framePose.Rot().Euler().X(),
1926 framePose.Rot().Euler().Y(),
1927 framePose.Rot().Euler().Z(),
1928 target_to_reference.Pos().X(),
1929 target_to_reference.Pos().Y(),
1930 target_to_reference.Pos().Z(),
1931 target_to_reference.Rot().Euler().X(),
1932 target_to_reference.Rot().Euler().Y(),
1933 target_to_reference.Rot().Euler().Z()
1935 transformWrench(target_force, target_torque, reference_force, reference_torque, target_to_reference);
1936 ROS_ERROR_NAMED(
"api_plugin",
"wrench defined as [%s]:[%f %f %f, %f %f %f] --> applied as [%s]:[%f %f %f, %f %f %f]",
1937 frame->GetName().c_str(),
1938 reference_force.X(),
1939 reference_force.Y(),
1940 reference_force.Z(),
1941 reference_torque.X(),
1942 reference_torque.Y(),
1943 reference_torque.Z(),
1944 body->GetName().c_str(),
1954 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
1956 ROS_INFO_NAMED(
"api_plugin",
"ApplyBodyWrench: reference_frame is empty/world/map, using inertial frame, transferring from body relative to inertial frame");
1958 #if GAZEBO_MAJOR_VERSION >= 8 1959 ignition::math::Pose3d target_to_reference = body->WorldPose();
1961 ignition::math::Pose3d target_to_reference = body->GetWorldPose().Ign();
1963 target_force = reference_force;
1964 target_torque = reference_torque;
1969 ROS_ERROR_NAMED(
"api_plugin",
"ApplyBodyWrench: reference_frame is not a valid entity name");
1970 res.success =
false;
1971 res.status_message =
"ApplyBodyWrench: reference_frame not found";
1981 wej->
force = target_force;
1982 wej->
torque = target_torque;
1984 #if GAZEBO_MAJOR_VERSION >= 8 1997 res.status_message =
"";
2003 TiXmlDocument doc_in;
2004 doc_in.Parse(model_xml.c_str());
2005 if (doc_in.FirstChild(
"robot"))
2014 TiXmlDocument doc_in;
2015 doc_in.Parse(model_xml.c_str());
2016 if (doc_in.FirstChild(
"gazebo") ||
2017 doc_in.FirstChild(
"sdf"))
2031 #if GAZEBO_MAJOR_VERSION >= 8 2036 if (simTime >= (*iter)->start_time)
2037 if (simTime <= (*iter)->start_time+(*iter)->duration ||
2038 (*iter)->duration.toSec() < 0.0)
2042 (*iter)->body->SetForce((*iter)->force);
2043 (*iter)->body->SetTorque((*iter)->torque);
2046 (*iter)->duration.
fromSec(0.0);
2049 if (simTime > (*iter)->start_time+(*iter)->duration &&
2050 (*iter)->duration.toSec() >= 0.0)
2070 #if GAZEBO_MAJOR_VERSION >= 8 2075 if (simTime >= (*iter)->start_time)
2076 if (simTime <= (*iter)->start_time+(*iter)->duration ||
2077 (*iter)->duration.toSec() < 0.0)
2080 (*iter)->joint->SetForce(0,(*iter)->force);
2082 (*iter)->duration.
fromSec(0.0);
2085 if (simTime > (*iter)->start_time+(*iter)->duration &&
2086 (*iter)->duration.toSec() >= 0.0)
2100 #if GAZEBO_MAJOR_VERSION >= 8 2101 gazebo::common::Time sim_time =
world_->SimTime();
2103 gazebo::common::Time sim_time =
world_->GetSimTime();
2108 gazebo::common::Time currentTime = gazebo::msgs::Convert( msg->sim_time() );
2109 rosgraph_msgs::Clock ros_time_;
2110 ros_time_.clock.fromSec(currentTime.Double());
2117 #if GAZEBO_MAJOR_VERSION >= 8 2118 gazebo::common::Time sim_time =
world_->SimTime();
2120 gazebo::common::Time sim_time =
world_->GetSimTime();
2125 #if GAZEBO_MAJOR_VERSION >= 8 2126 gazebo::common::Time currentTime =
world_->SimTime();
2128 gazebo::common::Time currentTime =
world_->GetSimTime();
2130 rosgraph_msgs::Clock ros_time_;
2131 ros_time_.clock.fromSec(currentTime.Double());
2139 gazebo_msgs::LinkStates link_states;
2142 #if GAZEBO_MAJOR_VERSION >= 8 2143 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
2145 gazebo::physics::ModelPtr model =
world_->ModelByIndex(i);
2147 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
2149 gazebo::physics::ModelPtr model =
world_->GetModel(i);
2152 for (
unsigned int j = 0 ; j < model->GetChildCount(); j ++)
2154 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(j));
2158 link_states.name.push_back(body->GetScopedName());
2159 geometry_msgs::Pose pose;
2160 #if GAZEBO_MAJOR_VERSION >= 8 2161 ignition::math::Pose3d body_pose = body->WorldPose();
2162 ignition::math::Vector3d linear_vel = body->WorldLinearVel();
2163 ignition::math::Vector3d angular_vel = body->WorldAngularVel();
2165 ignition::math::Pose3d body_pose = body->GetWorldPose().Ign();
2166 ignition::math::Vector3d linear_vel = body->GetWorldLinearVel().Ign();
2167 ignition::math::Vector3d angular_vel = body->GetWorldAngularVel().Ign();
2169 ignition::math::Vector3d pos = body_pose.Pos();
2170 ignition::math::Quaterniond rot = body_pose.Rot();
2171 pose.position.x = pos.X();
2172 pose.position.y = pos.Y();
2173 pose.position.z = pos.Z();
2174 pose.orientation.w = rot.W();
2175 pose.orientation.x = rot.X();
2176 pose.orientation.y = rot.Y();
2177 pose.orientation.z = rot.Z();
2178 link_states.pose.push_back(pose);
2179 geometry_msgs::Twist twist;
2180 twist.linear.x = linear_vel.X();
2181 twist.linear.y = linear_vel.Y();
2182 twist.linear.z = linear_vel.Z();
2183 twist.angular.x = angular_vel.X();
2184 twist.angular.y = angular_vel.Y();
2185 twist.angular.z = angular_vel.Z();
2186 link_states.twist.push_back(twist);
2196 gazebo_msgs::ModelStates model_states;
2199 #if GAZEBO_MAJOR_VERSION >= 8 2200 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
2202 gazebo::physics::ModelPtr model =
world_->ModelByIndex(i);
2203 ignition::math::Pose3d model_pose = model->WorldPose();
2204 ignition::math::Vector3d linear_vel = model->WorldLinearVel();
2205 ignition::math::Vector3d angular_vel = model->WorldAngularVel();
2207 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
2209 gazebo::physics::ModelPtr model =
world_->GetModel(i);
2210 ignition::math::Pose3d model_pose = model->GetWorldPose().Ign();
2211 ignition::math::Vector3d linear_vel = model->GetWorldLinearVel().Ign();
2212 ignition::math::Vector3d angular_vel = model->GetWorldAngularVel().Ign();
2214 ignition::math::Vector3d pos = model_pose.Pos();
2215 ignition::math::Quaterniond rot = model_pose.Rot();
2216 geometry_msgs::Pose pose;
2217 pose.position.x = pos.X();
2218 pose.position.y = pos.Y();
2219 pose.position.z = pos.Z();
2220 pose.orientation.w = rot.W();
2221 pose.orientation.x = rot.X();
2222 pose.orientation.y = rot.Y();
2223 pose.orientation.z = rot.Z();
2224 model_states.pose.push_back(pose);
2225 model_states.name.push_back(model->GetName());
2226 geometry_msgs::Twist twist;
2227 twist.linear.x = linear_vel.X();
2228 twist.linear.y = linear_vel.Y();
2229 twist.linear.z = linear_vel.Z();
2230 twist.angular.x = angular_vel.X();
2231 twist.angular.y = angular_vel.Y();
2232 twist.angular.z = angular_vel.Z();
2233 model_states.twist.push_back(twist);
2242 gazebo_msgs::GetPhysicsProperties srv;
2245 config.time_step = srv.response.time_step;
2246 config.max_update_rate = srv.response.max_update_rate;
2247 config.gravity_x = srv.response.gravity.x;
2248 config.gravity_y = srv.response.gravity.y;
2249 config.gravity_z = srv.response.gravity.z;
2250 config.auto_disable_bodies = srv.response.ode_config.auto_disable_bodies;
2251 config.sor_pgs_precon_iters = srv.response.ode_config.sor_pgs_precon_iters;
2252 config.sor_pgs_iters = srv.response.ode_config.sor_pgs_iters;
2253 config.sor_pgs_rms_error_tol = srv.response.ode_config.sor_pgs_rms_error_tol;
2254 config.sor_pgs_w = srv.response.ode_config.sor_pgs_w;
2255 config.contact_surface_layer = srv.response.ode_config.contact_surface_layer;
2256 config.contact_max_correcting_vel = srv.response.ode_config.contact_max_correcting_vel;
2257 config.cfm = srv.response.ode_config.cfm;
2258 config.erp = srv.response.ode_config.erp;
2259 config.max_contacts = srv.response.ode_config.max_contacts;
2264 bool changed =
false;
2265 gazebo_msgs::GetPhysicsProperties srv;
2269 if (config.time_step != srv.response.time_step) changed =
true;
2270 if (config.max_update_rate != srv.response.max_update_rate) changed =
true;
2271 if (config.gravity_x != srv.response.gravity.x) changed =
true;
2272 if (config.gravity_y != srv.response.gravity.y) changed =
true;
2273 if (config.gravity_z != srv.response.gravity.z) changed =
true;
2274 if (config.auto_disable_bodies != srv.response.ode_config.auto_disable_bodies) changed =
true;
2275 if ((uint32_t)config.sor_pgs_precon_iters != srv.response.ode_config.sor_pgs_precon_iters) changed =
true;
2276 if ((uint32_t)config.sor_pgs_iters != srv.response.ode_config.sor_pgs_iters) changed =
true;
2277 if (config.sor_pgs_rms_error_tol != srv.response.ode_config.sor_pgs_rms_error_tol) changed =
true;
2278 if (config.sor_pgs_w != srv.response.ode_config.sor_pgs_w) changed =
true;
2279 if (config.contact_surface_layer != srv.response.ode_config.contact_surface_layer) changed =
true;
2280 if (config.contact_max_correcting_vel != srv.response.ode_config.contact_max_correcting_vel) changed =
true;
2281 if (config.cfm != srv.response.ode_config.cfm) changed =
true;
2282 if (config.erp != srv.response.ode_config.erp) changed =
true;
2283 if ((uint32_t)config.max_contacts != srv.response.ode_config.max_contacts) changed =
true;
2288 gazebo_msgs::SetPhysicsProperties srv;
2289 srv.request.time_step = config.time_step ;
2290 srv.request.max_update_rate = config.max_update_rate ;
2291 srv.request.gravity.x = config.gravity_x ;
2292 srv.request.gravity.y = config.gravity_y ;
2293 srv.request.gravity.z = config.gravity_z ;
2294 srv.request.ode_config.auto_disable_bodies = config.auto_disable_bodies ;
2295 srv.request.ode_config.sor_pgs_precon_iters = config.sor_pgs_precon_iters ;
2296 srv.request.ode_config.sor_pgs_iters = config.sor_pgs_iters ;
2297 srv.request.ode_config.sor_pgs_rms_error_tol = config.sor_pgs_rms_error_tol ;
2298 srv.request.ode_config.sor_pgs_w = config.sor_pgs_w ;
2299 srv.request.ode_config.contact_surface_layer = config.contact_surface_layer ;
2300 srv.request.ode_config.contact_max_correcting_vel = config.contact_max_correcting_vel ;
2301 srv.request.ode_config.cfm = config.cfm ;
2302 srv.request.ode_config.erp = config.erp ;
2303 srv.request.ode_config.max_contacts = config.max_contacts ;
2305 ROS_INFO_NAMED(
"api_plugin",
"physics dynamics reconfigure update complete");
2307 ROS_INFO_NAMED(
"api_plugin",
"physics dynamics reconfigure complete");
2318 physics_reconfigure_get_client_.waitForExistence();
2325 ROS_INFO_NAMED(
"api_plugin",
"Physics dynamic reconfigure ready.");
2334 std::string open_bracket(
"<?");
2335 std::string close_bracket(
"?>");
2336 size_t pos1 = model_xml.find(open_bracket,0);
2337 size_t pos2 = model_xml.find(close_bracket,0);
2338 if (pos1 != std::string::npos && pos2 != std::string::npos)
2339 model_xml.replace(pos1,pos2-pos1+2,std::string(
""));
2343 const std::string &model_name,
2344 const ignition::math::Vector3d &initial_xyz,
2345 const ignition::math::Quaterniond &initial_q)
2350 TiXmlElement* pose_element;
2353 TiXmlElement* gazebo_tixml = gazebo_model_xml.FirstChildElement(
"sdf");
2356 ROS_WARN_NAMED(
"api_plugin",
"Could not find <sdf> element in sdf, so name and initial position cannot be applied");
2361 TiXmlElement* model_tixml = gazebo_tixml->FirstChildElement(
"model");
2365 if (model_tixml->Attribute(
"name") != NULL)
2368 model_tixml->RemoveAttribute(
"name");
2371 model_tixml->SetAttribute(
"name",model_name);
2376 TiXmlElement* world_tixml = gazebo_tixml->FirstChildElement(
"world");
2379 ROS_WARN_NAMED(
"api_plugin",
"Could not find <model> or <world> element in sdf, so name and initial position cannot be applied");
2383 model_tixml = world_tixml->FirstChildElement(
"include");
2386 ROS_WARN_NAMED(
"api_plugin",
"Could not find <include> element in sdf, so name and initial position cannot be applied");
2391 TiXmlElement* name_tixml = model_tixml->FirstChildElement(
"name");
2395 name_tixml =
new TiXmlElement(
"name");
2396 model_tixml->LinkEndChild(name_tixml);
2400 TiXmlText* text =
new TiXmlText(model_name);
2401 name_tixml->LinkEndChild( text );
2406 pose_element = model_tixml->FirstChildElement(
"pose");
2407 ignition::math::Pose3d model_pose;
2414 model_pose = this->
parsePose(pose_element->GetText());
2415 model_tixml->RemoveChild(pose_element);
2421 ignition::math::Pose3d new_model_pose = model_pose + ignition::math::Pose3d(initial_xyz, initial_q);
2424 std::ostringstream pose_stream;
2425 ignition::math::Vector3d model_rpy = new_model_pose.Rot().Euler();
2426 pose_stream << new_model_pose.Pos().X() <<
" " << new_model_pose.Pos().Y() <<
" " << new_model_pose.Pos().Z() <<
" " 2427 << model_rpy.X() <<
" " << model_rpy.Y() <<
" " << model_rpy.Z();
2430 TiXmlText* text =
new TiXmlText(pose_stream.str());
2431 TiXmlElement* new_pose_element =
new TiXmlElement(
"pose");
2432 new_pose_element->LinkEndChild(text);
2433 model_tixml->LinkEndChild(new_pose_element);
2439 std::vector<std::string> pieces;
2440 std::vector<double> vals;
2442 boost::split(pieces, str, boost::is_any_of(
" "));
2443 for (
unsigned int i = 0; i < pieces.size(); ++i)
2445 if (pieces[i] !=
"")
2449 vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
2451 catch(boost::bad_lexical_cast &e)
2453 sdferr <<
"xml key [" << str
2454 <<
"][" << i <<
"] value [" << pieces[i]
2455 <<
"] is not a valid double from a 3-tuple\n";
2456 return ignition::math::Pose3d();
2461 if (vals.size() == 6)
2462 return ignition::math::Pose3d(vals[0], vals[1], vals[2], vals[3], vals[4], vals[5]);
2465 ROS_ERROR_NAMED(
"api_plugin",
"Beware: failed to parse string [%s] as ignition::math::Pose3d, returning zeros.", str.c_str());
2466 return ignition::math::Pose3d();
2472 std::vector<std::string> pieces;
2473 std::vector<double> vals;
2475 boost::split(pieces, str, boost::is_any_of(
" "));
2476 for (
unsigned int i = 0; i < pieces.size(); ++i)
2478 if (pieces[i] !=
"")
2482 vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
2484 catch(boost::bad_lexical_cast &e)
2486 sdferr <<
"xml key [" << str
2487 <<
"][" << i <<
"] value [" << pieces[i]
2488 <<
"] is not a valid double from a 3-tuple\n";
2489 return ignition::math::Vector3d();
2494 if (vals.size() == 3)
2495 return ignition::math::Vector3d(vals[0], vals[1], vals[2]);
2498 ROS_ERROR_NAMED(
"api_plugin",
"Beware: failed to parse string [%s] as ignition::math::Vector3d, returning zeros.", str.c_str());
2499 return ignition::math::Vector3d();
2504 const ignition::math::Vector3d &initial_xyz,
2505 const ignition::math::Quaterniond &initial_q)
2507 TiXmlElement* model_tixml = (gazebo_model_xml.FirstChildElement(
"robot"));
2512 TiXmlElement* origin_key = model_tixml->FirstChildElement(
"origin");
2516 origin_key =
new TiXmlElement(
"origin");
2517 model_tixml->LinkEndChild(origin_key);
2520 ignition::math::Vector3d xyz;
2521 ignition::math::Vector3d rpy;
2522 if (origin_key->Attribute(
"xyz"))
2524 xyz = this->
parseVector3(origin_key->Attribute(
"xyz"));
2525 origin_key->RemoveAttribute(
"xyz");
2527 if (origin_key->Attribute(
"rpy"))
2529 rpy = this->
parseVector3(origin_key->Attribute(
"rpy"));
2530 origin_key->RemoveAttribute(
"rpy");
2534 ignition::math::Pose3d model_pose = ignition::math::Pose3d(xyz, ignition::math::Quaterniond(rpy))
2535 + ignition::math::Pose3d(initial_xyz, initial_q);
2537 std::ostringstream xyz_stream;
2538 xyz_stream << model_pose.Pos().X() <<
" " << model_pose.Pos().Y() <<
" " << model_pose.Pos().Z();
2540 std::ostringstream rpy_stream;
2541 ignition::math::Vector3d model_rpy = model_pose.Rot().Euler();
2542 rpy_stream << model_rpy.X() <<
" " << model_rpy.Y() <<
" " << model_rpy.Z();
2544 origin_key->SetAttribute(
"xyz",xyz_stream.str());
2545 origin_key->SetAttribute(
"rpy",rpy_stream.str());
2548 ROS_WARN_NAMED(
"api_plugin",
"Could not find <model> element in sdf, so name and initial position is not applied");
2553 TiXmlElement* model_tixml = gazebo_model_xml.FirstChildElement(
"robot");
2557 if (model_tixml->Attribute(
"name") != NULL)
2560 model_tixml->RemoveAttribute(
"name");
2563 model_tixml->SetAttribute(
"name",model_name);
2566 ROS_WARN_NAMED(
"api_plugin",
"Could not find <robot> element in URDF, name not replaced");
2571 TiXmlNode* child = 0;
2572 child = model_xml->IterateChildren(child);
2573 while (child != NULL)
2575 if (child->Type() == TiXmlNode::TINYXML_ELEMENT &&
2576 child->ValueStr().compare(std::string(
"plugin")) == 0)
2578 if (child->FirstChildElement(
"robotNamespace") == NULL)
2580 TiXmlElement* child_elem = child->ToElement()->FirstChildElement(
"robotNamespace");
2583 child->ToElement()->RemoveChild(child_elem);
2584 child_elem = child->ToElement()->FirstChildElement(
"robotNamespace");
2586 TiXmlElement* key =
new TiXmlElement(
"robotNamespace");
2588 key->LinkEndChild(val);
2589 child->ToElement()->LinkEndChild(key);
2593 child = model_xml->IterateChildren(child);
2598 gazebo_msgs::SpawnModel::Response &res)
2600 std::string entity_type = gazebo_model_xml.RootElement()->FirstChild()->Value();
2602 std::transform(entity_type.begin(), entity_type.end(), entity_type.begin(), ::tolower);
2604 bool isLight = (entity_type ==
"light");
2607 std::ostringstream stream;
2608 stream << gazebo_model_xml;
2609 std::string gazebo_model_xml_string = stream.str();
2610 ROS_DEBUG_NAMED(
"api_plugin.xml",
"Gazebo Model XML\n\n%s\n\n ",gazebo_model_xml_string.c_str());
2613 gazebo::msgs::Factory msg;
2614 gazebo::msgs::Init(msg,
"spawn_model");
2615 msg.set_sdf( gazebo_model_xml_string );
2621 gazebo::msgs::Request *entity_info_msg = gazebo::msgs::CreateRequest(
"entity_info", model_name);
2625 #if GAZEBO_MAJOR_VERSION >= 8 2626 gazebo::physics::ModelPtr model =
world_->ModelByName(model_name);
2627 gazebo::physics::LightPtr light =
world_->LightByName(model_name);
2629 gazebo::physics::ModelPtr model =
world_->GetModel(model_name);
2630 gazebo::physics::LightPtr light =
world_->Light(model_name);
2632 if ((isLight && light != NULL) || (model != NULL))
2634 ROS_ERROR_NAMED(
"api_plugin",
"SpawnModel: Failure - model name %s already exist.",model_name.c_str());
2635 res.success =
false;
2636 res.status_message =
"SpawnModel: Failure - entity already exists.";
2645 sdf_light.SetFromString(gazebo_model_xml_string);
2646 gazebo::msgs::Light msg = gazebo::msgs::LightFromSDF(sdf_light.Root()->GetElement(
"light"));
2647 msg.set_name(model_name);
2666 res.success =
false;
2667 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;
2673 #if GAZEBO_MAJOR_VERSION >= 8 2674 if ((isLight &&
world_->LightByName(model_name) != NULL)
2675 || (
world_->ModelByName(model_name) != NULL))
2677 if ((isLight &&
world_->Light(model_name) != NULL)
2678 || (
world_->GetModel(model_name) != NULL))
2684 <<
" for entity " << model_name <<
" to spawn");
2691 res.status_message =
"SpawnModel: Successfully spawned entity";
bool getLinkProperties(gazebo_msgs::GetLinkProperties::Request &req, gazebo_msgs::GetLinkProperties::Response &res)
void shutdownSignal()
Detect if sig-int shutdown signal is recieved
#define ROS_DEBUG_ONCE_NAMED(name,...)
ros::ServiceServer reset_simulation_service_
ignition::math::Vector3d torque
bool getPhysicsProperties(gazebo_msgs::GetPhysicsProperties::Request &req, gazebo_msgs::GetPhysicsProperties::Response &res)
gazebo::physics::LinkPtr body
ros::ServiceServer apply_body_wrench_service_
bool setJointProperties(gazebo_msgs::SetJointProperties::Request &req, gazebo_msgs::SetJointProperties::Response &res)
void updateURDFModelPose(TiXmlDocument &gazebo_model_xml, const ignition::math::Vector3d &initial_xyz, const ignition::math::Quaterniond &initial_q)
Update the model pose of the URDF file before sending to Gazebo.
bool setPhysicsProperties(gazebo_msgs::SetPhysicsProperties::Request &req, gazebo_msgs::SetPhysicsProperties::Response &res)
gazebo::event::ConnectionPtr time_update_event_
bool setModelConfiguration(gazebo_msgs::SetModelConfiguration::Request &req, gazebo_msgs::SetModelConfiguration::Response &res)
bool getModelState(gazebo_msgs::GetModelState::Request &req, gazebo_msgs::GetModelState::Response &res)
ros::ServiceServer set_physics_properties_service_
void onLinkStatesDisconnect()
ros::ServiceServer get_model_properties_service_
#define ROS_INFO_NAMED(name,...)
ros::ServiceServer unpause_physics_service_
#define ROS_DEBUG_STREAM_NAMED(name, args)
void forceJointSchedulerSlot()
bool setLinkProperties(gazebo_msgs::SetLinkProperties::Request &req, gazebo_msgs::SetLinkProperties::Response &res)
boost::shared_ptr< dynamic_reconfigure::Server< gazebo_ros::PhysicsConfig > > physics_reconfigure_srv_
void publish(const boost::shared_ptr< M > &message) const
#define ROS_WARN_NAMED(name,...)
void loadGazeboRosApiPlugin(std::string world_name)
Connect to Gazebo via its plugin interface, get a pointer to the world, start events.
gazebo::common::Time last_pub_clock_time_
ros::ServiceServer spawn_urdf_model_service_
ros::ServiceServer get_light_properties_service_
dynamic_reconfigure::Server< gazebo_ros::PhysicsConfig >::CallbackType physics_reconfigure_callback_
bool isURDF(std::string model_xml)
utility for checking if string is in URDF format
boost::shared_ptr< ros::NodeHandle > nh_
void onLinkStatesConnect()
void wrenchBodySchedulerSlot()
boost::shared_ptr< boost::thread > physics_reconfigure_thread_
ROSCPP_DECL bool isInitialized()
void physicsReconfigureThread()
waits for the rest of Gazebo to be ready before initializing the dynamic reconfigure services ...
bool setLinkState(gazebo_msgs::SetLinkState::Request &req, gazebo_msgs::SetLinkState::Response &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
gazebo::transport::PublisherPtr request_pub_
ros::ServiceServer clear_body_wrenches_service_
ros::Subscriber set_link_state_topic_
ignition::math::Pose3d parsePose(const std::string &str)
convert xml to Pose
void onModelStatesConnect()
ros::ServiceServer get_link_properties_service_
ros::ServiceServer set_model_configuration_service_
void advertiseServices()
advertise services
gazebo::physics::WorldPtr world_
int pub_model_states_connection_count_
ros::ServiceClient physics_reconfigure_set_client_
ros::ServiceServer delete_light_service_
bool resetSimulation(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer delete_model_service_
bool unpausePhysics(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer apply_joint_effort_service_
ros::ServiceServer clear_joint_forces_service_
std::vector< GazeboRosApiPlugin::ForceJointJob * > force_joint_jobs_
std::map< std::string, unsigned int > access_count_get_model_state_
index counters to count the accesses on models via GetModelState
#define ROS_DEBUG_NAMED(name,...)
boost::mutex lock_
A mutex to lock access to fields that are used in ROS message callbacks.
void transformWrench(ignition::math::Vector3d &target_force, ignition::math::Vector3d &target_torque, const ignition::math::Vector3d &reference_force, const ignition::math::Vector3d &reference_torque, const ignition::math::Pose3d &target_to_reference)
helper function for applyBodyWrench shift wrench from reference frame to target frame ...
ros::ServiceServer set_model_state_service_
ros::ServiceClient physics_reconfigure_get_client_
ros::ServiceServer reset_world_service_
gazebo::physics::JointPtr joint
bool applyJointEffort(gazebo_msgs::ApplyJointEffort::Request &req, gazebo_msgs::ApplyJointEffort::Response &res)
void updateSDFAttributes(TiXmlDocument &gazebo_model_xml, const std::string &model_name, const ignition::math::Vector3d &initial_xyz, const ignition::math::Quaterniond &initial_q)
Update the model name and pose of the SDF file before sending to Gazebo.
bool getJointProperties(gazebo_msgs::GetJointProperties::Request &req, gazebo_msgs::GetJointProperties::Response &res)
ros::ServiceServer get_joint_properties_service_
bool getWorldProperties(gazebo_msgs::GetWorldProperties::Request &req, gazebo_msgs::GetWorldProperties::Response &res)
void updateModelState(const gazebo_msgs::ModelState::ConstPtr &model_state)
void publishModelStates()
gazebo::event::ConnectionPtr sigint_event_
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ros::Publisher pub_clock_
gazebo::event::ConnectionPtr pub_model_states_event_
bool deleteLight(gazebo_msgs::DeleteLight::Request &req, gazebo_msgs::DeleteLight::Response &res)
delete a given light by name
gazebo::event::ConnectionPtr wrench_update_event_
void Load(int argc, char **argv)
Gazebo-inherited load function.
gazebo::transport::PublisherPtr factory_light_pub_
bool pausePhysics(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
ros::ServiceServer set_link_properties_service_
ros::ServiceServer set_light_properties_service_
int pub_link_states_connection_count_
bool clearBodyWrenches(gazebo_msgs::BodyRequest::Request &req, gazebo_msgs::BodyRequest::Response &res)
gazebo::transport::SubscriberPtr response_sub_
GazeboRosApiPlugin()
Constructor.
bool getModelProperties(gazebo_msgs::GetModelProperties::Request &req, gazebo_msgs::GetModelProperties::Response &res)
boost::shared_ptr< boost::thread > gazebo_callback_queue_thread_
ros::CallbackQueue gazebo_queue_
gazebo::event::ConnectionPtr force_update_event_
bool spawnURDFModel(gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
Function for inserting a URDF into Gazebo from ROS Service Call.
void walkChildAddRobotNamespace(TiXmlNode *model_xml)
std::string robot_namespace_
bool resetWorld(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
#define ROS_DEBUG_STREAM_ONCE_NAMED(name, args)
bool isSDF(std::string model_xml)
utility for checking if string is in SDF format
ROSLIB_DECL std::string getPath(const std::string &package_name)
boost::shared_ptr< ros::AsyncSpinner > async_ros_spin_
A plugin loaded within the gzserver on startup.
bool applyBodyWrench(gazebo_msgs::ApplyBodyWrench::Request &req, gazebo_msgs::ApplyBodyWrench::Response &res)
ros::ServiceServer get_model_state_service_
void onModelStatesDisconnect()
void physicsReconfigureCallback(gazebo_ros::PhysicsConfig &config, uint32_t level)
Used for the dynamic reconfigure callback function template.
bool clearJointForces(gazebo_msgs::JointRequest::Request &req, gazebo_msgs::JointRequest::Response &res)
ros::ServiceServer set_joint_properties_service_
gazebo::transport::PublisherPtr factory_pub_
gazebo::event::ConnectionPtr load_gazebo_ros_api_plugin_event_
bool spawnAndConform(TiXmlDocument &gazebo_model_xml, const std::string &model_name, gazebo_msgs::SpawnModel::Response &res)
ros::ServiceServer spawn_sdf_model_service_
ignition::math::Vector3d parseVector3(const std::string &str)
convert xml to Pose
bool getLightProperties(gazebo_msgs::GetLightProperties::Request &req, gazebo_msgs::GetLightProperties::Response &res)
ros::ServiceServer get_world_properties_service_
ros::ServiceServer set_link_state_service_
std::vector< GazeboRosApiPlugin::WrenchBodyJob * > wrench_body_jobs_
gazebo::event::ConnectionPtr pub_link_states_event_
#define ROS_FATAL_NAMED(name,...)
#define ROS_ERROR_NAMED(name,...)
ros::ServiceServer get_link_state_service_
void updateLinkState(const gazebo_msgs::LinkState::ConstPtr &link_state)
gazebo::transport::NodePtr gazebonode_
void gazeboQueueThread()
ros queue thread for this node
bool setLightProperties(gazebo_msgs::SetLightProperties::Request &req, gazebo_msgs::SetLightProperties::Response &res)
bool deleteModel(gazebo_msgs::DeleteModel::Request &req, gazebo_msgs::DeleteModel::Response &res)
delete model given name
bool spawnSDFModel(gazebo_msgs::SpawnModel::Request &req, gazebo_msgs::SpawnModel::Response &res)
Both SDFs and converted URDFs get sent to this function for further manipulation from a ROS Service c...
ros::Publisher pub_link_states_
ros::Subscriber set_model_state_topic_
void onResponse(ConstResponsePtr &response)
Unused.
void stripXmlDeclaration(std::string &model_xml)
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
ros::ServiceServer pause_physics_service_
boost::shared_ptr< void > VoidPtr
bool getLinkState(gazebo_msgs::GetLinkState::Request &req, gazebo_msgs::GetLinkState::Response &res)
void updateURDFName(TiXmlDocument &gazebo_model_xml, const std::string &model_name)
Update the model name of the URDF file before sending to Gazebo.
bool enable_ros_network_
enable the communication of gazebo information using ROS service/topics
~GazeboRosApiPlugin()
Destructor.
ros::ServiceServer get_physics_properties_service_
ros::Publisher pub_model_states_
ignition::math::Vector3d force
bool setModelState(gazebo_msgs::SetModelState::Request &req, gazebo_msgs::SetModelState::Response &res)
gazebo::transport::PublisherPtr light_modify_pub_
#define ROS_WARN_STREAM_NAMED(name, args)
bool physics_reconfigure_initialized_