23 #include <gazebo/common/Events.hh> 24 #include <gazebo/gazebo_config.h> 33 plugin_loaded_(false),
35 pub_link_states_connection_count_(0),
36 pub_model_states_connection_count_(0),
37 pub_performance_metrics_connection_count_(0),
38 physics_reconfigure_initialized_(false),
39 pub_clock_frequency_(0),
40 world_created_(false),
41 enable_ros_network_(true)
131 ROS_ERROR_NAMED(
"api_plugin",
"Something other than this gazebo_ros_api plugin started ros::init(...), command line arguments may not be parsed properly.");
139 std::this_thread::sleep_for(std::chrono::microseconds(500*1000));
169 ROS_INFO_NAMED(
"api_plugin",
"Finished loading Gazebo ROS API Plugin.");
186 world_ = gazebo::physics::get_world(world_name);
191 ROS_FATAL_NAMED(
"api_plugin",
"cannot load gazebo ros api server plugin, physics::get_world() fails to return world");
195 gazebonode_ = gazebo::transport::NodePtr(
new gazebo::transport::Node());
208 pub_clock_ =
nh_->advertise<rosgraph_msgs::Clock>(
"/clock", 10);
215 if(!(
nh_->hasParam(
"/use_sim_time")))
216 nh_->setParam(
"/use_sim_time",
true);
219 #if GAZEBO_MAJOR_VERSION >= 8 235 #ifdef GAZEBO_ROS_HAS_PERFORMANCE_METRICS 238 gazebo_msgs::PerformanceMetrics msg_ros;
240 msg_ros.real_time_factor = msg->real_time_factor();
241 for (
auto sensor: msg->sensor())
244 sensor_msgs.sim_update_rate = sensor.sim_update_rate();
245 sensor_msgs.real_update_rate = sensor.real_update_rate();
246 sensor_msgs.name = sensor.name();
248 if (sensor.has_fps())
250 sensor_msgs.fps = sensor.fps();
253 sensor_msgs.fps = -1;
256 msg_ros.sensors.push_back(sensor_msgs);
265 static const double timeout = 0.001;
276 ROS_INFO_NAMED(
"api_plugin",
"ROS gazebo topics/services are disabled");
281 std::string spawn_sdf_model_service_name(
"spawn_sdf_model");
283 ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
284 spawn_sdf_model_service_name,
290 std::string spawn_urdf_model_service_name(
"spawn_urdf_model");
292 ros::AdvertiseServiceOptions::create<gazebo_msgs::SpawnModel>(
293 spawn_urdf_model_service_name,
299 std::string delete_model_service_name(
"delete_model");
301 ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteModel>(
302 delete_model_service_name,
308 std::string delete_light_service_name(
"delete_light");
310 ros::AdvertiseServiceOptions::create<gazebo_msgs::DeleteLight>(
311 delete_light_service_name,
317 std::string get_model_properties_service_name(
"get_model_properties");
319 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelProperties>(
320 get_model_properties_service_name,
326 std::string get_model_state_service_name(
"get_model_state");
328 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetModelState>(
329 get_model_state_service_name,
335 std::string get_world_properties_service_name(
"get_world_properties");
337 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetWorldProperties>(
338 get_world_properties_service_name,
344 std::string get_joint_properties_service_name(
"get_joint_properties");
346 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetJointProperties>(
347 get_joint_properties_service_name,
353 std::string get_link_properties_service_name(
"get_link_properties");
355 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkProperties>(
356 get_link_properties_service_name,
362 std::string get_link_state_service_name(
"get_link_state");
364 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLinkState>(
365 get_link_state_service_name,
371 std::string get_light_properties_service_name(
"get_light_properties");
373 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetLightProperties>(
374 get_light_properties_service_name,
380 std::string set_light_properties_service_name(
"set_light_properties");
382 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLightProperties>(
383 set_light_properties_service_name,
389 std::string get_physics_properties_service_name(
"get_physics_properties");
391 ros::AdvertiseServiceOptions::create<gazebo_msgs::GetPhysicsProperties>(
392 get_physics_properties_service_name,
399 ros::AdvertiseOptions::create<gazebo_msgs::LinkStates>(
408 ros::AdvertiseOptions::create<gazebo_msgs::ModelStates>(
415 #ifdef GAZEBO_ROS_HAS_PERFORMANCE_METRICS 418 ros::AdvertiseOptions::create<gazebo_msgs::PerformanceMetrics>(
419 "performance_metrics",10,
420 boost::bind(&GazeboRosApiPlugin::onPerformanceMetricsConnect,
this),
421 boost::bind(&GazeboRosApiPlugin::onPerformanceMetricsDisconnect,
this),
427 std::string set_link_properties_service_name(
"set_link_properties");
429 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkProperties>(
430 set_link_properties_service_name,
436 std::string set_physics_properties_service_name(
"set_physics_properties");
438 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetPhysicsProperties>(
439 set_physics_properties_service_name,
445 std::string set_model_state_service_name(
"set_model_state");
447 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelState>(
448 set_model_state_service_name,
454 std::string set_model_configuration_service_name(
"set_model_configuration");
456 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetModelConfiguration>(
457 set_model_configuration_service_name,
463 std::string set_joint_properties_service_name(
"set_joint_properties");
465 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetJointProperties>(
466 set_joint_properties_service_name,
472 std::string set_link_state_service_name(
"set_link_state");
474 ros::AdvertiseServiceOptions::create<gazebo_msgs::SetLinkState>(
475 set_link_state_service_name,
483 ros::SubscribeOptions::create<gazebo_msgs::LinkState>(
491 ros::SubscribeOptions::create<gazebo_msgs::ModelState>(
492 "set_model_state",10,
498 std::string pause_physics_service_name(
"pause_physics");
500 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
501 pause_physics_service_name,
507 std::string unpause_physics_service_name(
"unpause_physics");
509 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
510 unpause_physics_service_name,
516 std::string apply_body_wrench_service_name(
"apply_body_wrench");
518 ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyBodyWrench>(
519 apply_body_wrench_service_name,
525 std::string apply_joint_effort_service_name(
"apply_joint_effort");
527 ros::AdvertiseServiceOptions::create<gazebo_msgs::ApplyJointEffort>(
528 apply_joint_effort_service_name,
534 std::string clear_joint_forces_service_name(
"clear_joint_forces");
536 ros::AdvertiseServiceOptions::create<gazebo_msgs::JointRequest>(
537 clear_joint_forces_service_name,
543 std::string clear_body_wrenches_service_name(
"clear_body_wrenches");
545 ros::AdvertiseServiceOptions::create<gazebo_msgs::BodyRequest>(
546 clear_body_wrenches_service_name,
552 std::string reset_simulation_service_name(
"reset_simulation");
554 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
555 reset_simulation_service_name,
561 std::string reset_world_service_name(
"reset_world");
563 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
564 reset_world_service_name,
584 #ifdef GAZEBO_ROS_HAS_PERFORMANCE_METRICS 585 void GazeboRosApiPlugin::onPerformanceMetricsConnect()
591 &GazeboRosApiPlugin::onPerformanceMetrics,
this);
595 void GazeboRosApiPlugin::onPerformanceMetricsDisconnect()
602 ROS_ERROR_NAMED(
"api_plugin",
"One too many disconnect from pub_performance_metrics_ in gazebo_ros.cpp? something weird");
614 ROS_ERROR_NAMED(
"api_plugin",
"One too many disconnect from pub_link_states_ in gazebo_ros.cpp? something weird");
625 ROS_ERROR_NAMED(
"api_plugin",
"One too many disconnect from pub_model_states_ in gazebo_ros.cpp? something weird");
630 gazebo_msgs::SpawnModel::Response &res)
636 std::string model_xml = req.model_xml;
640 ROS_ERROR_NAMED(
"api_plugin",
"SpawnModel: Failure - entity format is invalid.");
642 res.status_message =
"SpawnModel: Failure - entity format is invalid.";
650 std::string open_bracket(
"<?");
651 std::string close_bracket(
"?>");
652 size_t pos1 = model_xml.find(open_bracket,0);
653 size_t pos2 = model_xml.find(close_bracket,0);
654 if (pos1 != std::string::npos && pos2 != std::string::npos)
655 model_xml.replace(pos1,pos2-pos1+2,std::string(
""));
660 std::string open_comment(
"<!--");
661 std::string close_comment(
"-->");
663 while((pos1 = model_xml.find(open_comment,0)) != std::string::npos){
664 size_t pos2 = model_xml.find(close_comment,0);
665 if (pos2 != std::string::npos)
666 model_xml.replace(pos1,pos2-pos1+3,std::string(
""));
672 std::string package_prefix(
"package://");
673 size_t pos1 = model_xml.find(package_prefix,0);
674 while (pos1 != std::string::npos)
676 size_t pos2 = model_xml.find(
"/", pos1+10);
678 if (pos2 == std::string::npos || pos1 >= pos2)
684 std::string package_name = model_xml.substr(pos1+10,pos2-pos1-10);
687 if (package_path.empty())
689 ROS_FATAL_NAMED(
"api_plugin",
"Package[%s] does not have a path",package_name.c_str());
691 res.status_message =
"urdf reference package name does not exist: " + package_name;
694 ROS_DEBUG_ONCE_NAMED(
"api_plugin",
"Package name [%s] has path [%s]", package_name.c_str(), package_path.c_str());
696 model_xml.replace(pos1,(pos2-pos1),package_path);
697 pos1 = model_xml.find(package_prefix, pos1);
702 req.model_xml = model_xml;
709 gazebo_msgs::SpawnModel::Response &res)
712 std::string model_name = req.model_name;
718 ignition::math::Vector3d initial_xyz(req.initial_pose.position.x,req.initial_pose.position.y,req.initial_pose.position.z);
720 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);
723 #if GAZEBO_MAJOR_VERSION >= 8 724 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
726 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
731 #if GAZEBO_MAJOR_VERSION >= 8 732 ignition::math::Pose3d frame_pose = frame->WorldPose();
734 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
736 initial_xyz = frame_pose.Pos() + frame_pose.Rot().RotateVector(initial_xyz);
737 initial_q = frame_pose.Rot() * initial_q;
741 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
743 ROS_DEBUG_NAMED(
"api_plugin",
"SpawnModel: reference_frame is empty/world/map, using inertial frame");
748 res.status_message =
"SpawnModel: reference reference_frame not found, did you forget to scope the link by model name?";
753 std::string model_xml = req.model_xml;
761 TiXmlDocument gazebo_model_xml;
762 gazebo_model_xml.Parse(model_xml.c_str());
765 if (
isSDF(model_xml))
775 TiXmlNode* model_tixml = gazebo_model_xml.FirstChild(
"sdf");
776 model_tixml = (!model_tixml) ?
777 gazebo_model_xml.FirstChild(
"gazebo") : model_tixml;
784 ROS_WARN_NAMED(
"api_plugin",
"Unable to add robot namespace to xml");
788 else if (
isURDF(model_xml))
798 TiXmlNode* model_tixml = gazebo_model_xml.FirstChild(
"robot");
805 ROS_WARN_NAMED(
"api_plugin",
"Unable to add robot namespace to xml");
811 ROS_ERROR_NAMED(
"api_plugin",
"GazeboRosApiPlugin SpawnModel Failure: input xml format not recognized");
813 res.status_message =
"GazeboRosApiPlugin SpawnModel Failure: input model_xml not SDF or URDF, or cannot be converted to Gazebo compatible format.";
822 gazebo_msgs::DeleteModel::Response &res)
825 #if GAZEBO_MAJOR_VERSION >= 8 826 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
828 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
832 ROS_ERROR_NAMED(
"api_plugin",
"DeleteModel: model [%s] does not exist",req.model_name.c_str());
834 res.status_message =
"DeleteModel: model does not exist";
839 for (
unsigned int i = 0 ; i < model->GetChildCount(); i ++)
841 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
850 gazebo::physics::Joint_V joints = model->GetJoints();
851 for (
unsigned int i=0;i< joints.size(); i++)
858 gazebo::msgs::Request *msg = gazebo::msgs::CreateRequest(
"entity_delete",req.model_name);
870 res.status_message =
"DeleteModel: Model pushed to delete queue, but delete service timed out waiting for model to disappear from simulation";
875 #if GAZEBO_MAJOR_VERSION >= 8 876 if (!
world_->ModelByName(req.model_name))
break;
878 if (!
world_->GetModel(req.model_name))
break;
881 ROS_DEBUG_NAMED(
"api_plugin",
"Waiting for model deletion (%s)",req.model_name.c_str());
882 std::this_thread::sleep_for(std::chrono::microseconds(1000));
887 res.status_message =
"DeleteModel: successfully deleted model";
892 gazebo_msgs::DeleteLight::Response &res)
894 #if GAZEBO_MAJOR_VERSION >= 8 895 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
897 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
900 if (phy_light == NULL)
903 res.status_message =
"DeleteLight: Requested light " + req.light_name +
" not found!";
907 gazebo::msgs::Request* msg = gazebo::msgs::CreateRequest(
"entity_delete", req.light_name);
913 for (
int i = 0; i < 100; i++)
915 #if GAZEBO_MAJOR_VERSION >= 8 916 phy_light =
world_->LightByName(req.light_name);
918 phy_light =
world_->Light(req.light_name);
920 if (phy_light == NULL)
923 res.status_message =
"DeleteLight: " + req.light_name +
" successfully deleted";
927 std::this_thread::sleep_for(std::chrono::microseconds(100000));
931 res.status_message =
"DeleteLight: Timeout reached while removing light \"" + req.light_name
938 gazebo_msgs::GetModelState::Response &res)
940 #if GAZEBO_MAJOR_VERSION >= 8 941 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
942 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.relative_entity_name);
944 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
945 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.relative_entity_name);
949 ROS_ERROR_NAMED(
"api_plugin",
"GetModelState: model [%s] does not exist",req.model_name.c_str());
951 res.status_message =
"GetModelState: model does not exist";
971 res.header.seq = it->second;
974 res.header.frame_id = req.relative_entity_name;
978 #if GAZEBO_MAJOR_VERSION >= 8 979 ignition::math::Pose3d model_pose = model->WorldPose();
980 ignition::math::Vector3d model_linear_vel = model->WorldLinearVel();
981 ignition::math::Vector3d model_angular_vel = model->WorldAngularVel();
983 ignition::math::Pose3d model_pose = model->GetWorldPose().Ign();
984 ignition::math::Vector3d model_linear_vel = model->GetWorldLinearVel().Ign();
985 ignition::math::Vector3d model_angular_vel = model->GetWorldAngularVel().Ign();
987 ignition::math::Vector3d model_pos = model_pose.Pos();
988 ignition::math::Quaterniond model_rot = model_pose.Rot();
995 #if GAZEBO_MAJOR_VERSION >= 8 996 ignition::math::Pose3d frame_pose = frame->WorldPose();
997 ignition::math::Vector3d frame_vpos = frame->WorldLinearVel();
998 ignition::math::Vector3d frame_veul = frame->WorldAngularVel();
1000 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
1001 ignition::math::Vector3d frame_vpos = frame->GetWorldLinearVel().Ign();
1002 ignition::math::Vector3d frame_veul = frame->GetWorldAngularVel().Ign();
1004 ignition::math::Pose3d model_rel_pose = model_pose - frame_pose;
1005 model_pos = model_rel_pose.Pos();
1006 model_rot = model_rel_pose.Rot();
1008 model_linear_vel = frame_pose.Rot().RotateVectorReverse(model_linear_vel - frame_vpos);
1009 model_angular_vel = frame_pose.Rot().RotateVectorReverse(model_angular_vel - frame_veul);
1012 else if (req.relative_entity_name ==
"" || req.relative_entity_name ==
"world" || req.relative_entity_name ==
"map" || req.relative_entity_name ==
"/map")
1014 ROS_DEBUG_NAMED(
"api_plugin",
"GetModelState: relative_entity_name is empty/world/map, using inertial frame");
1018 res.success =
false;
1019 res.status_message =
"GetModelState: reference relative_entity_name not found, did you forget to scope the body by model name?";
1024 res.pose.position.x = model_pos.X();
1025 res.pose.position.y = model_pos.Y();
1026 res.pose.position.z = model_pos.Z();
1027 res.pose.orientation.w = model_rot.W();
1028 res.pose.orientation.x = model_rot.X();
1029 res.pose.orientation.y = model_rot.Y();
1030 res.pose.orientation.z = model_rot.Z();
1032 res.twist.linear.x = model_linear_vel.X();
1033 res.twist.linear.y = model_linear_vel.Y();
1034 res.twist.linear.z = model_linear_vel.Z();
1035 res.twist.angular.x = model_angular_vel.X();
1036 res.twist.angular.y = model_angular_vel.Y();
1037 res.twist.angular.z = model_angular_vel.Z();
1040 res.status_message =
"GetModelState: got properties";
1047 gazebo_msgs::GetModelProperties::Response &res)
1049 #if GAZEBO_MAJOR_VERSION >= 8 1050 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_name);
1052 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_name);
1056 ROS_ERROR_NAMED(
"api_plugin",
"GetModelProperties: model [%s] does not exist",req.model_name.c_str());
1057 res.success =
false;
1058 res.status_message =
"GetModelProperties: model does not exist";
1064 gazebo::physics::ModelPtr parent_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetParent());
1065 if (parent_model) res.parent_model_name = parent_model->GetName();
1068 res.body_names.clear();
1069 res.geom_names.clear();
1070 for (
unsigned int i = 0 ; i < model->GetChildCount(); i ++)
1072 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(i));
1075 res.body_names.push_back(body->GetName());
1077 for (
unsigned int j = 0; j < body->GetChildCount() ; j++)
1079 gazebo::physics::CollisionPtr geom = boost::dynamic_pointer_cast<gazebo::physics::Collision>(body->GetChild(j));
1081 res.geom_names.push_back(geom->GetName());
1087 res.joint_names.clear();
1089 gazebo::physics::Joint_V joints = model->GetJoints();
1090 for (
unsigned int i=0;i< joints.size(); i++)
1091 res.joint_names.push_back( joints[i]->GetName() );
1094 res.child_model_names.clear();
1095 for (
unsigned int j = 0; j < model->GetChildCount(); j++)
1097 gazebo::physics::ModelPtr child_model = boost::dynamic_pointer_cast<gazebo::physics::Model>(model->GetChild(j));
1099 res.child_model_names.push_back(child_model->GetName() );
1103 res.is_static = model->IsStatic();
1106 res.status_message =
"GetModelProperties: got properties";
1113 gazebo_msgs::GetWorldProperties::Response &res)
1115 res.model_names.clear();
1116 #if GAZEBO_MAJOR_VERSION >= 8 1117 res.sim_time =
world_->SimTime().Double();
1118 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1119 res.model_names.push_back(
world_->ModelByIndex(i)->GetName());
1121 res.sim_time =
world_->GetSimTime().Double();
1122 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1123 res.model_names.push_back(
world_->GetModel(i)->GetName());
1126 res.rendering_enabled =
true;
1128 res.status_message =
"GetWorldProperties: got properties";
1133 gazebo_msgs::GetJointProperties::Response &res)
1135 gazebo::physics::JointPtr joint;
1136 #if GAZEBO_MAJOR_VERSION >= 8 1137 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1139 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1141 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1143 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1150 res.success =
false;
1151 res.status_message =
"GetJointProperties: joint not found";
1157 res.type = res.REVOLUTE;
1159 res.damping.clear();
1162 res.position.clear();
1163 #if GAZEBO_MAJOR_VERSION >= 8 1164 res.position.push_back(joint->Position(0));
1166 res.position.push_back(joint->GetAngle(0).Radian());
1170 res.rate.push_back(joint->GetVelocity(0));
1173 res.status_message =
"GetJointProperties: got properties";
1179 gazebo_msgs::GetLinkProperties::Response &res)
1181 #if GAZEBO_MAJOR_VERSION >= 8 1182 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1184 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1188 res.success =
false;
1189 res.status_message =
"GetLinkProperties: link not found, did you forget to scope the link by model name?";
1195 res.gravity_mode = body->GetGravityMode();
1197 gazebo::physics::InertialPtr inertia = body->GetInertial();
1199 #if GAZEBO_MAJOR_VERSION >= 8 1200 res.mass = body->GetInertial()->Mass();
1202 res.ixx = inertia->IXX();
1203 res.iyy = inertia->IYY();
1204 res.izz = inertia->IZZ();
1205 res.ixy = inertia->IXY();
1206 res.ixz = inertia->IXZ();
1207 res.iyz = inertia->IYZ();
1209 ignition::math::Vector3d com = body->GetInertial()->CoG();
1211 res.mass = body->GetInertial()->GetMass();
1213 res.ixx = inertia->GetIXX();
1214 res.iyy = inertia->GetIYY();
1215 res.izz = inertia->GetIZZ();
1216 res.ixy = inertia->GetIXY();
1217 res.ixz = inertia->GetIXZ();
1218 res.iyz = inertia->GetIYZ();
1220 ignition::math::Vector3d com = body->GetInertial()->GetCoG().Ign();
1222 res.com.position.x = com.X();
1223 res.com.position.y = com.Y();
1224 res.com.position.z = com.Z();
1225 res.com.orientation.x = 0;
1226 res.com.orientation.y = 0;
1227 res.com.orientation.z = 0;
1228 res.com.orientation.w = 1;
1231 res.status_message =
"GetLinkProperties: got properties";
1237 gazebo_msgs::GetLinkState::Response &res)
1239 #if GAZEBO_MAJOR_VERSION >= 8 1240 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1241 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
1243 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1244 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
1249 res.success =
false;
1250 res.status_message =
"GetLinkState: link not found, did you forget to scope the link by model name?";
1256 #if GAZEBO_MAJOR_VERSION >= 8 1257 ignition::math::Pose3d body_pose = body->WorldPose();
1258 ignition::math::Vector3d body_vpos = body->WorldLinearVel();
1259 ignition::math::Vector3d body_veul = body->WorldAngularVel();
1261 ignition::math::Pose3d body_pose = body->GetWorldPose().Ign();
1262 ignition::math::Vector3d body_vpos = body->GetWorldLinearVel().Ign();
1263 ignition::math::Vector3d body_veul = body->GetWorldAngularVel().Ign();
1269 #if GAZEBO_MAJOR_VERSION >= 8 1270 ignition::math::Pose3d frame_pose = frame->WorldPose();
1271 ignition::math::Vector3d frame_vpos = frame->WorldLinearVel();
1272 ignition::math::Vector3d frame_veul = frame->WorldAngularVel();
1274 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
1275 ignition::math::Vector3d frame_vpos = frame->GetWorldLinearVel().Ign();
1276 ignition::math::Vector3d frame_veul = frame->GetWorldAngularVel().Ign();
1278 body_pose = body_pose - frame_pose;
1280 body_vpos = frame_pose.Rot().RotateVectorReverse(body_vpos - frame_vpos);
1281 body_veul = frame_pose.Rot().RotateVectorReverse(body_veul - frame_veul);
1284 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
1286 ROS_DEBUG_NAMED(
"api_plugin",
"GetLinkState: reference_frame is empty/world/map, using inertial frame");
1290 res.success =
false;
1291 res.status_message =
"GetLinkState: reference reference_frame not found, did you forget to scope the link by model name?";
1295 res.link_state.link_name = req.link_name;
1296 res.link_state.pose.position.x = body_pose.Pos().X();
1297 res.link_state.pose.position.y = body_pose.Pos().Y();
1298 res.link_state.pose.position.z = body_pose.Pos().Z();
1299 res.link_state.pose.orientation.x = body_pose.Rot().X();
1300 res.link_state.pose.orientation.y = body_pose.Rot().Y();
1301 res.link_state.pose.orientation.z = body_pose.Rot().Z();
1302 res.link_state.pose.orientation.w = body_pose.Rot().W();
1303 res.link_state.twist.linear.x = body_vpos.X();
1304 res.link_state.twist.linear.y = body_vpos.Y();
1305 res.link_state.twist.linear.z = body_vpos.Z();
1306 res.link_state.twist.angular.x = body_veul.X();
1307 res.link_state.twist.angular.y = body_veul.Y();
1308 res.link_state.twist.angular.z = body_veul.Z();
1309 res.link_state.reference_frame = req.reference_frame;
1312 res.status_message =
"GetLinkState: got state";
1317 gazebo_msgs::GetLightProperties::Response &res)
1319 #if GAZEBO_MAJOR_VERSION >= 8 1320 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
1322 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
1325 if (phy_light == NULL)
1327 res.success =
false;
1328 res.status_message =
"getLightProperties: Requested light " + req.light_name +
" not found!";
1332 gazebo::msgs::Light light;
1333 phy_light->FillMsg(light);
1335 res.diffuse.r = light.diffuse().r();
1336 res.diffuse.g = light.diffuse().g();
1337 res.diffuse.b = light.diffuse().b();
1338 res.diffuse.a = light.diffuse().a();
1340 res.attenuation_constant = light.attenuation_constant();
1341 res.attenuation_linear = light.attenuation_linear();
1342 res.attenuation_quadratic = light.attenuation_quadratic();
1351 gazebo_msgs::SetLightProperties::Response &res)
1353 #if GAZEBO_MAJOR_VERSION >= 8 1354 gazebo::physics::LightPtr phy_light =
world_->LightByName(req.light_name);
1356 gazebo::physics::LightPtr phy_light =
world_->Light(req.light_name);
1359 if (phy_light == NULL)
1361 res.success =
false;
1362 res.status_message =
"setLightProperties: Requested light " + req.light_name +
" not found!";
1366 gazebo::msgs::Light light;
1368 phy_light->FillMsg(light);
1370 light.mutable_diffuse()->set_r(req.diffuse.r);
1371 light.mutable_diffuse()->set_g(req.diffuse.g);
1372 light.mutable_diffuse()->set_b(req.diffuse.b);
1373 light.mutable_diffuse()->set_a(req.diffuse.a);
1375 light.set_attenuation_constant(req.attenuation_constant);
1376 light.set_attenuation_linear(req.attenuation_linear);
1377 light.set_attenuation_quadratic(req.attenuation_quadratic);
1388 gazebo_msgs::SetLinkProperties::Response &res)
1390 #if GAZEBO_MAJOR_VERSION >= 8 1391 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_name));
1393 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_name));
1397 res.success =
false;
1398 res.status_message =
"SetLinkProperties: link not found, did you forget to scope the link by model name?";
1403 gazebo::physics::InertialPtr mass = body->GetInertial();
1406 mass->SetCoG(ignition::math::Vector3d(req.com.position.x,req.com.position.y,req.com.position.z));
1407 mass->SetInertiaMatrix(req.ixx,req.iyy,req.izz,req.ixy,req.ixz,req.iyz);
1408 mass->SetMass(req.mass);
1409 body->SetGravityMode(req.gravity_mode);
1412 res.status_message =
"SetLinkProperties: properties set";
1418 gazebo_msgs::SetPhysicsProperties::Response &res)
1421 bool is_paused =
world_->IsPaused();
1423 world_->SetGravity(ignition::math::Vector3d(req.gravity.x,req.gravity.y,req.gravity.z));
1426 #if GAZEBO_MAJOR_VERSION >= 8 1427 gazebo::physics::PhysicsEnginePtr pe = (
world_->Physics());
1429 gazebo::physics::PhysicsEnginePtr pe = (
world_->GetPhysicsEngine());
1431 pe->SetMaxStepSize(req.time_step);
1432 pe->SetRealTimeUpdateRate(req.max_update_rate);
1434 if (pe->GetType() ==
"ode")
1437 pe->SetAutoDisableFlag(req.ode_config.auto_disable_bodies);
1438 pe->SetParam(
"precon_iters",
int(req.ode_config.sor_pgs_precon_iters));
1439 pe->SetParam(
"iters",
int(req.ode_config.sor_pgs_iters));
1440 pe->SetParam(
"sor", req.ode_config.sor_pgs_w);
1441 pe->SetParam(
"cfm", req.ode_config.cfm);
1442 pe->SetParam(
"erp", req.ode_config.erp);
1443 pe->SetParam(
"contact_surface_layer",
1444 req.ode_config.contact_surface_layer);
1445 pe->SetParam(
"contact_max_correcting_vel",
1446 req.ode_config.contact_max_correcting_vel);
1447 pe->SetParam(
"max_contacts",
int(req.ode_config.max_contacts));
1449 world_->SetPaused(is_paused);
1452 res.status_message =
"physics engine updated";
1457 ROS_ERROR_NAMED(
"api_plugin",
"ROS set_physics_properties service call does not yet support physics engine [%s].", pe->GetType().c_str());
1458 res.success =
false;
1459 res.status_message =
"Physics engine [" + pe->GetType() +
"]: set_physics_properties not supported.";
1465 gazebo_msgs::GetPhysicsProperties::Response &res)
1468 #if GAZEBO_MAJOR_VERSION >= 8 1469 gazebo::physics::PhysicsEnginePtr pe = (
world_->Physics());
1471 gazebo::physics::PhysicsEnginePtr pe = (
world_->GetPhysicsEngine());
1473 res.time_step = pe->GetMaxStepSize();
1474 res.pause =
world_->IsPaused();
1475 res.max_update_rate = pe->GetRealTimeUpdateRate();
1476 ignition::math::Vector3d gravity =
world_->Gravity();
1477 res.gravity.x = gravity.X();
1478 res.gravity.y = gravity.Y();
1479 res.gravity.z = gravity.Z();
1482 if (pe->GetType() ==
"ode")
1484 res.ode_config.auto_disable_bodies =
1485 pe->GetAutoDisableFlag();
1486 res.ode_config.sor_pgs_precon_iters = boost::any_cast<
int>(
1487 pe->GetParam(
"precon_iters"));
1488 res.ode_config.sor_pgs_iters = boost::any_cast<
int>(
1489 pe->GetParam(
"iters"));
1490 res.ode_config.sor_pgs_w = boost::any_cast<
double>(
1491 pe->GetParam(
"sor"));
1492 res.ode_config.contact_surface_layer = boost::any_cast<
double>(
1493 pe->GetParam(
"contact_surface_layer"));
1494 res.ode_config.contact_max_correcting_vel = boost::any_cast<
double>(
1495 pe->GetParam(
"contact_max_correcting_vel"));
1496 res.ode_config.cfm = boost::any_cast<
double>(
1497 pe->GetParam(
"cfm"));
1498 res.ode_config.erp = boost::any_cast<
double>(
1499 pe->GetParam(
"erp"));
1500 res.ode_config.max_contacts = boost::any_cast<
int>(
1501 pe->GetParam(
"max_contacts"));
1504 res.status_message =
"GetPhysicsProperties: got properties";
1509 ROS_ERROR_NAMED(
"api_plugin",
"ROS get_physics_properties service call does not yet support physics engine [%s].", pe->GetType().c_str());
1510 res.success =
false;
1511 res.status_message =
"Physics engine [" + pe->GetType() +
"]: get_physics_properties not supported.";
1517 gazebo_msgs::SetJointProperties::Response &res)
1520 gazebo::physics::JointPtr joint;
1521 #if GAZEBO_MAJOR_VERSION >= 8 1522 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1524 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1526 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1528 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1535 res.success =
false;
1536 res.status_message =
"SetJointProperties: joint not found";
1541 for(
unsigned int i=0;i< req.ode_joint_config.damping.size();i++)
1542 joint->SetDamping(i,req.ode_joint_config.damping[i]);
1543 for(
unsigned int i=0;i< req.ode_joint_config.hiStop.size();i++)
1544 joint->SetParam(
"hi_stop",i,req.ode_joint_config.hiStop[i]);
1545 for(
unsigned int i=0;i< req.ode_joint_config.loStop.size();i++)
1546 joint->SetParam(
"lo_stop",i,req.ode_joint_config.loStop[i]);
1547 for(
unsigned int i=0;i< req.ode_joint_config.erp.size();i++)
1548 joint->SetParam(
"erp",i,req.ode_joint_config.erp[i]);
1549 for(
unsigned int i=0;i< req.ode_joint_config.cfm.size();i++)
1550 joint->SetParam(
"cfm",i,req.ode_joint_config.cfm[i]);
1551 for(
unsigned int i=0;i< req.ode_joint_config.stop_erp.size();i++)
1552 joint->SetParam(
"stop_erp",i,req.ode_joint_config.stop_erp[i]);
1553 for(
unsigned int i=0;i< req.ode_joint_config.stop_cfm.size();i++)
1554 joint->SetParam(
"stop_cfm",i,req.ode_joint_config.stop_cfm[i]);
1555 for(
unsigned int i=0;i< req.ode_joint_config.fudge_factor.size();i++)
1556 joint->SetParam(
"fudge_factor",i,req.ode_joint_config.fudge_factor[i]);
1557 for(
unsigned int i=0;i< req.ode_joint_config.fmax.size();i++)
1558 joint->SetParam(
"fmax",i,req.ode_joint_config.fmax[i]);
1559 for(
unsigned int i=0;i< req.ode_joint_config.vel.size();i++)
1560 joint->SetParam(
"vel",i,req.ode_joint_config.vel[i]);
1563 res.status_message =
"SetJointProperties: properties set";
1569 gazebo_msgs::SetModelState::Response &res)
1571 ignition::math::Vector3d target_pos(req.model_state.pose.position.x,req.model_state.pose.position.y,req.model_state.pose.position.z);
1572 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);
1573 target_rot.Normalize();
1574 ignition::math::Pose3d target_pose(target_pos,target_rot);
1575 ignition::math::Vector3d target_pos_dot(req.model_state.twist.linear.x,req.model_state.twist.linear.y,req.model_state.twist.linear.z);
1576 ignition::math::Vector3d target_rot_dot(req.model_state.twist.angular.x,req.model_state.twist.angular.y,req.model_state.twist.angular.z);
1578 #if GAZEBO_MAJOR_VERSION >= 8 1579 gazebo::physics::ModelPtr model =
world_->ModelByName(req.model_state.model_name);
1581 gazebo::physics::ModelPtr model =
world_->GetModel(req.model_state.model_name);
1585 ROS_ERROR_NAMED(
"api_plugin",
"Updating ModelState: model [%s] does not exist",req.model_state.model_name.c_str());
1586 res.success =
false;
1587 res.status_message =
"SetModelState: model does not exist";
1592 #if GAZEBO_MAJOR_VERSION >= 8 1593 gazebo::physics::EntityPtr relative_entity =
world_->EntityByName(req.model_state.reference_frame);
1595 gazebo::physics::EntityPtr relative_entity =
world_->GetEntity(req.model_state.reference_frame);
1597 if (relative_entity)
1599 #if GAZEBO_MAJOR_VERSION >= 8 1600 ignition::math::Pose3d frame_pose = relative_entity->WorldPose();
1602 ignition::math::Pose3d frame_pose = relative_entity->GetWorldPose().Ign();
1605 target_pose = target_pose + frame_pose;
1609 target_pos_dot = frame_pose.Rot().RotateVector(target_pos_dot);
1610 target_rot_dot = frame_pose.Rot().RotateVector(target_rot_dot);
1613 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" )
1615 ROS_DEBUG_NAMED(
"api_plugin",
"Updating ModelState: reference frame is empty/world/map, usig inertial frame");
1619 ROS_ERROR_NAMED(
"api_plugin",
"Updating ModelState: for model[%s], specified reference frame entity [%s] does not exist",
1620 req.model_state.model_name.c_str(),req.model_state.reference_frame.c_str());
1621 res.success =
false;
1622 res.status_message =
"SetModelState: specified reference frame entity does not exist";
1627 bool is_paused =
world_->IsPaused();
1629 model->SetWorldPose(target_pose);
1630 world_->SetPaused(is_paused);
1631 #if GAZEBO_MAJOR_VERSION >= 8 1639 model->SetLinearVel(target_pos_dot);
1640 model->SetAngularVel(target_rot_dot);
1643 res.status_message =
"SetModelState: set model state done";
1650 gazebo_msgs::SetModelState::Response res;
1651 gazebo_msgs::SetModelState::Request req;
1652 req.model_state = *model_state;
1657 gazebo_msgs::ApplyJointEffort::Response &res)
1659 gazebo::physics::JointPtr joint;
1660 #if GAZEBO_MAJOR_VERSION >= 8 1661 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
1663 joint =
world_->ModelByIndex(i)->GetJoint(req.joint_name);
1665 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
1667 joint =
world_->GetModel(i)->GetJoint(req.joint_name);
1673 fjj->
force = req.effort;
1675 #if GAZEBO_MAJOR_VERSION >= 8 1688 res.status_message =
"ApplyJointEffort: effort set";
1693 res.success =
false;
1694 res.status_message =
"ApplyJointEffort: joint not found";
1706 world_->ResetEntities(gazebo::physics::Base::MODEL);
1718 world_->SetPaused(
false);
1723 gazebo_msgs::JointRequest::Response &res)
1736 if ((*iter)->joint->GetName() == joint_name)
1751 gazebo_msgs::BodyRequest::Response &res)
1765 if ((*iter)->body->GetScopedName() == body_name)
1780 gazebo_msgs::SetModelConfiguration::Response &res)
1782 std::string gazebo_model_name = req.model_name;
1785 #if GAZEBO_MAJOR_VERSION >= 8 1786 gazebo::physics::ModelPtr gazebo_model =
world_->ModelByName(req.model_name);
1788 gazebo::physics::ModelPtr gazebo_model =
world_->GetModel(req.model_name);
1792 ROS_ERROR_NAMED(
"api_plugin",
"SetModelConfiguration: model [%s] does not exist",gazebo_model_name.c_str());
1793 res.success =
false;
1794 res.status_message =
"SetModelConfiguration: model does not exist";
1798 if (req.joint_names.size() == req.joint_positions.size())
1800 std::map<std::string, double> joint_position_map;
1801 for (
unsigned int i = 0; i < req.joint_names.size(); i++)
1803 joint_position_map[req.joint_names[i]] = req.joint_positions[i];
1807 bool is_paused =
world_->IsPaused();
1808 if (!is_paused)
world_->SetPaused(
true);
1810 gazebo_model->SetJointPositions(joint_position_map);
1813 world_->SetPaused(is_paused);
1816 res.status_message =
"SetModelConfiguration: success";
1821 res.success =
false;
1822 res.status_message =
"SetModelConfiguration: joint name and position list have different lengths";
1828 gazebo_msgs::SetLinkState::Response &res)
1830 #if GAZEBO_MAJOR_VERSION >= 8 1831 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_state.link_name));
1832 gazebo::physics::LinkPtr frame = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.link_state.reference_frame));
1834 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.link_state.link_name));
1835 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.link_state.reference_frame);
1839 ROS_ERROR_NAMED(
"api_plugin",
"Updating LinkState: link [%s] does not exist",req.link_state.link_name.c_str());
1840 res.success =
false;
1841 res.status_message =
"SetLinkState: link does not exist";
1848 ignition::math::Vector3d target_pos(req.link_state.pose.position.x,req.link_state.pose.position.y,req.link_state.pose.position.z);
1849 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);
1850 ignition::math::Pose3d target_pose(target_pos,target_rot);
1851 ignition::math::Vector3d target_linear_vel(req.link_state.twist.linear.x,req.link_state.twist.linear.y,req.link_state.twist.linear.z);
1852 ignition::math::Vector3d target_angular_vel(req.link_state.twist.angular.x,req.link_state.twist.angular.y,req.link_state.twist.angular.z);
1856 #if GAZEBO_MAJOR_VERSION >= 8 1857 ignition::math::Pose3d frame_pose = frame->WorldPose();
1858 ignition::math::Vector3d frame_linear_vel = frame->WorldLinearVel();
1859 ignition::math::Vector3d frame_angular_vel = frame->WorldAngularVel();
1861 ignition::math::Pose3d frame_pose = frame->GetWorldPose().Ign();
1862 ignition::math::Vector3d frame_linear_vel = frame->GetWorldLinearVel().Ign();
1863 ignition::math::Vector3d frame_angular_vel = frame->GetWorldAngularVel().Ign();
1865 ignition::math::Vector3d frame_pos = frame_pose.Pos();
1866 ignition::math::Quaterniond frame_rot = frame_pose.Rot();
1869 target_pose = target_pose + frame_pose;
1871 target_linear_vel -= frame_linear_vel;
1872 target_angular_vel -= frame_angular_vel;
1874 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")
1876 ROS_INFO_NAMED(
"api_plugin",
"Updating LinkState: reference_frame is empty/world/map, using inertial frame");
1880 ROS_ERROR_NAMED(
"api_plugin",
"Updating LinkState: reference_frame is not a valid entity name");
1881 res.success =
false;
1882 res.status_message =
"SetLinkState: failed";
1889 bool is_paused =
world_->IsPaused();
1890 if (!is_paused)
world_->SetPaused(
true);
1891 body->SetWorldPose(target_pose);
1892 world_->SetPaused(is_paused);
1895 body->SetLinearVel(target_linear_vel);
1896 body->SetAngularVel(target_angular_vel);
1899 res.status_message =
"SetLinkState: success";
1905 gazebo_msgs::SetLinkState::Request req;
1906 gazebo_msgs::SetLinkState::Response res;
1907 req.link_state = *link_state;
1912 const ignition::math::Vector3d &reference_force,
1913 const ignition::math::Vector3d &reference_torque,
1914 const ignition::math::Pose3d &target_to_reference )
1917 target_force = target_to_reference.Rot().RotateVector(reference_force);
1919 target_torque = target_to_reference.Rot().RotateVector(reference_torque);
1922 target_torque = target_torque + target_to_reference.Pos().Cross(target_force);
1926 gazebo_msgs::ApplyBodyWrench::Response &res)
1928 #if GAZEBO_MAJOR_VERSION >= 8 1929 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->EntityByName(req.body_name));
1930 gazebo::physics::EntityPtr frame =
world_->EntityByName(req.reference_frame);
1932 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(
world_->GetEntity(req.body_name));
1933 gazebo::physics::EntityPtr frame =
world_->GetEntity(req.reference_frame);
1937 ROS_ERROR_NAMED(
"api_plugin",
"ApplyBodyWrench: body [%s] does not exist",req.body_name.c_str());
1938 res.success =
false;
1939 res.status_message =
"ApplyBodyWrench: body does not exist";
1944 ignition::math::Vector3d reference_force(req.wrench.force.x,req.wrench.force.y,req.wrench.force.z);
1945 ignition::math::Vector3d reference_torque(req.wrench.torque.x,req.wrench.torque.y,req.wrench.torque.z);
1946 ignition::math::Vector3d reference_point(req.reference_point.x,req.reference_point.y,req.reference_point.z);
1948 ignition::math::Vector3d target_force;
1949 ignition::math::Vector3d target_torque;
1953 reference_torque = reference_torque + reference_point.Cross(reference_force);
1964 #if GAZEBO_MAJOR_VERSION >= 8 1965 ignition::math::Pose3d framePose = frame->WorldPose();
1966 ignition::math::Pose3d bodyPose = body->WorldPose();
1968 ignition::math::Pose3d framePose = frame->GetWorldPose().Ign();
1969 ignition::math::Pose3d bodyPose = body->GetWorldPose().Ign();
1971 ignition::math::Pose3d target_to_reference = framePose - bodyPose;
1972 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]",
1976 bodyPose.Rot().Euler().X(),
1977 bodyPose.Rot().Euler().Y(),
1978 bodyPose.Rot().Euler().Z(),
1979 framePose.Pos().X(),
1980 framePose.Pos().Y(),
1981 framePose.Pos().Z(),
1982 framePose.Rot().Euler().X(),
1983 framePose.Rot().Euler().Y(),
1984 framePose.Rot().Euler().Z(),
1985 target_to_reference.Pos().X(),
1986 target_to_reference.Pos().Y(),
1987 target_to_reference.Pos().Z(),
1988 target_to_reference.Rot().Euler().X(),
1989 target_to_reference.Rot().Euler().Y(),
1990 target_to_reference.Rot().Euler().Z()
1992 transformWrench(target_force, target_torque, reference_force, reference_torque, target_to_reference);
1993 ROS_ERROR_NAMED(
"api_plugin",
"wrench defined as [%s]:[%f %f %f, %f %f %f] --> applied as [%s]:[%f %f %f, %f %f %f]",
1994 frame->GetName().c_str(),
1995 reference_force.X(),
1996 reference_force.Y(),
1997 reference_force.Z(),
1998 reference_torque.X(),
1999 reference_torque.Y(),
2000 reference_torque.Z(),
2001 body->GetName().c_str(),
2011 else if (req.reference_frame ==
"" || req.reference_frame ==
"world" || req.reference_frame ==
"map" || req.reference_frame ==
"/map")
2013 ROS_INFO_NAMED(
"api_plugin",
"ApplyBodyWrench: reference_frame is empty/world/map, using inertial frame, transferring from body relative to inertial frame");
2015 #if GAZEBO_MAJOR_VERSION >= 8 2016 ignition::math::Pose3d target_to_reference = body->WorldPose();
2018 ignition::math::Pose3d target_to_reference = body->GetWorldPose().Ign();
2020 target_force = reference_force;
2021 target_torque = reference_torque;
2026 ROS_ERROR_NAMED(
"api_plugin",
"ApplyBodyWrench: reference_frame is not a valid entity name");
2027 res.success =
false;
2028 res.status_message =
"ApplyBodyWrench: reference_frame not found";
2038 wej->
force = target_force;
2039 wej->
torque = target_torque;
2041 #if GAZEBO_MAJOR_VERSION >= 8 2054 res.status_message =
"";
2060 TiXmlDocument doc_in;
2061 doc_in.Parse(model_xml.c_str());
2062 if (doc_in.FirstChild(
"robot"))
2071 TiXmlDocument doc_in;
2072 doc_in.Parse(model_xml.c_str());
2073 if (doc_in.FirstChild(
"gazebo") ||
2074 doc_in.FirstChild(
"sdf"))
2088 #if GAZEBO_MAJOR_VERSION >= 8 2093 if (simTime >= (*iter)->start_time)
2094 if (simTime <= (*iter)->start_time+(*iter)->duration ||
2095 (*iter)->duration.toSec() < 0.0)
2099 (*iter)->body->SetForce((*iter)->force);
2100 (*iter)->body->SetTorque((*iter)->torque);
2103 (*iter)->duration.
fromSec(0.0);
2106 if (simTime > (*iter)->start_time+(*iter)->duration &&
2107 (*iter)->duration.toSec() >= 0.0)
2127 #if GAZEBO_MAJOR_VERSION >= 8 2132 if (simTime >= (*iter)->start_time)
2133 if (simTime <= (*iter)->start_time+(*iter)->duration ||
2134 (*iter)->duration.toSec() < 0.0)
2137 (*iter)->joint->SetForce(0,(*iter)->force);
2139 (*iter)->duration.
fromSec(0.0);
2142 if (simTime > (*iter)->start_time+(*iter)->duration &&
2143 (*iter)->duration.toSec() >= 0.0)
2156 #if GAZEBO_MAJOR_VERSION >= 8 2157 gazebo::common::Time sim_time =
world_->SimTime();
2159 gazebo::common::Time sim_time =
world_->GetSimTime();
2164 #if GAZEBO_MAJOR_VERSION >= 8 2165 gazebo::common::Time currentTime =
world_->SimTime();
2167 gazebo::common::Time currentTime =
world_->GetSimTime();
2169 rosgraph_msgs::Clock ros_time_;
2170 ros_time_.clock.fromSec(currentTime.Double());
2178 gazebo_msgs::LinkStates link_states;
2181 #if GAZEBO_MAJOR_VERSION >= 8 2182 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
2184 gazebo::physics::ModelPtr model =
world_->ModelByIndex(i);
2186 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
2188 gazebo::physics::ModelPtr model =
world_->GetModel(i);
2191 for (
unsigned int j = 0 ; j < model->GetChildCount(); j ++)
2193 gazebo::physics::LinkPtr body = boost::dynamic_pointer_cast<gazebo::physics::Link>(model->GetChild(j));
2197 link_states.name.push_back(body->GetScopedName());
2198 geometry_msgs::Pose pose;
2199 #if GAZEBO_MAJOR_VERSION >= 8 2200 ignition::math::Pose3d body_pose = body->WorldPose();
2201 ignition::math::Vector3d linear_vel = body->WorldLinearVel();
2202 ignition::math::Vector3d angular_vel = body->WorldAngularVel();
2204 ignition::math::Pose3d body_pose = body->GetWorldPose().Ign();
2205 ignition::math::Vector3d linear_vel = body->GetWorldLinearVel().Ign();
2206 ignition::math::Vector3d angular_vel = body->GetWorldAngularVel().Ign();
2208 ignition::math::Vector3d pos = body_pose.Pos();
2209 ignition::math::Quaterniond rot = body_pose.Rot();
2210 pose.position.x = pos.X();
2211 pose.position.y = pos.Y();
2212 pose.position.z = pos.Z();
2213 pose.orientation.w = rot.W();
2214 pose.orientation.x = rot.X();
2215 pose.orientation.y = rot.Y();
2216 pose.orientation.z = rot.Z();
2217 link_states.pose.push_back(pose);
2218 geometry_msgs::Twist twist;
2219 twist.linear.x = linear_vel.X();
2220 twist.linear.y = linear_vel.Y();
2221 twist.linear.z = linear_vel.Z();
2222 twist.angular.x = angular_vel.X();
2223 twist.angular.y = angular_vel.Y();
2224 twist.angular.z = angular_vel.Z();
2225 link_states.twist.push_back(twist);
2235 gazebo_msgs::ModelStates model_states;
2238 #if GAZEBO_MAJOR_VERSION >= 8 2239 for (
unsigned int i = 0; i <
world_->ModelCount(); i ++)
2241 gazebo::physics::ModelPtr model =
world_->ModelByIndex(i);
2242 ignition::math::Pose3d model_pose = model->WorldPose();
2243 ignition::math::Vector3d linear_vel = model->WorldLinearVel();
2244 ignition::math::Vector3d angular_vel = model->WorldAngularVel();
2246 for (
unsigned int i = 0; i <
world_->GetModelCount(); i ++)
2248 gazebo::physics::ModelPtr model =
world_->GetModel(i);
2249 ignition::math::Pose3d model_pose = model->GetWorldPose().Ign();
2250 ignition::math::Vector3d linear_vel = model->GetWorldLinearVel().Ign();
2251 ignition::math::Vector3d angular_vel = model->GetWorldAngularVel().Ign();
2253 ignition::math::Vector3d pos = model_pose.Pos();
2254 ignition::math::Quaterniond rot = model_pose.Rot();
2255 geometry_msgs::Pose pose;
2256 pose.position.x = pos.X();
2257 pose.position.y = pos.Y();
2258 pose.position.z = pos.Z();
2259 pose.orientation.w = rot.W();
2260 pose.orientation.x = rot.X();
2261 pose.orientation.y = rot.Y();
2262 pose.orientation.z = rot.Z();
2263 model_states.pose.push_back(pose);
2264 model_states.name.push_back(model->GetName());
2265 geometry_msgs::Twist twist;
2266 twist.linear.x = linear_vel.X();
2267 twist.linear.y = linear_vel.Y();
2268 twist.linear.z = linear_vel.Z();
2269 twist.angular.x = angular_vel.X();
2270 twist.angular.y = angular_vel.Y();
2271 twist.angular.z = angular_vel.Z();
2272 model_states.twist.push_back(twist);
2281 gazebo_msgs::GetPhysicsProperties srv;
2284 config.time_step = srv.response.time_step;
2285 config.max_update_rate = srv.response.max_update_rate;
2286 config.gravity_x = srv.response.gravity.x;
2287 config.gravity_y = srv.response.gravity.y;
2288 config.gravity_z = srv.response.gravity.z;
2289 config.auto_disable_bodies = srv.response.ode_config.auto_disable_bodies;
2290 config.sor_pgs_precon_iters = srv.response.ode_config.sor_pgs_precon_iters;
2291 config.sor_pgs_iters = srv.response.ode_config.sor_pgs_iters;
2292 config.sor_pgs_rms_error_tol = srv.response.ode_config.sor_pgs_rms_error_tol;
2293 config.sor_pgs_w = srv.response.ode_config.sor_pgs_w;
2294 config.contact_surface_layer = srv.response.ode_config.contact_surface_layer;
2295 config.contact_max_correcting_vel = srv.response.ode_config.contact_max_correcting_vel;
2296 config.cfm = srv.response.ode_config.cfm;
2297 config.erp = srv.response.ode_config.erp;
2298 config.max_contacts = srv.response.ode_config.max_contacts;
2303 bool changed =
false;
2304 gazebo_msgs::GetPhysicsProperties srv;
2308 if (config.time_step != srv.response.time_step) changed =
true;
2309 if (config.max_update_rate != srv.response.max_update_rate) changed =
true;
2310 if (config.gravity_x != srv.response.gravity.x) changed =
true;
2311 if (config.gravity_y != srv.response.gravity.y) changed =
true;
2312 if (config.gravity_z != srv.response.gravity.z) changed =
true;
2313 if (config.auto_disable_bodies != srv.response.ode_config.auto_disable_bodies) changed =
true;
2314 if ((uint32_t)config.sor_pgs_precon_iters != srv.response.ode_config.sor_pgs_precon_iters) changed =
true;
2315 if ((uint32_t)config.sor_pgs_iters != srv.response.ode_config.sor_pgs_iters) changed =
true;
2316 if (config.sor_pgs_rms_error_tol != srv.response.ode_config.sor_pgs_rms_error_tol) changed =
true;
2317 if (config.sor_pgs_w != srv.response.ode_config.sor_pgs_w) changed =
true;
2318 if (config.contact_surface_layer != srv.response.ode_config.contact_surface_layer) changed =
true;
2319 if (config.contact_max_correcting_vel != srv.response.ode_config.contact_max_correcting_vel) changed =
true;
2320 if (config.cfm != srv.response.ode_config.cfm) changed =
true;
2321 if (config.erp != srv.response.ode_config.erp) changed =
true;
2322 if ((uint32_t)config.max_contacts != srv.response.ode_config.max_contacts) changed =
true;
2327 gazebo_msgs::SetPhysicsProperties srv;
2328 srv.request.time_step = config.time_step ;
2329 srv.request.max_update_rate = config.max_update_rate ;
2330 srv.request.gravity.x = config.gravity_x ;
2331 srv.request.gravity.y = config.gravity_y ;
2332 srv.request.gravity.z = config.gravity_z ;
2333 srv.request.ode_config.auto_disable_bodies = config.auto_disable_bodies ;
2334 srv.request.ode_config.sor_pgs_precon_iters = config.sor_pgs_precon_iters ;
2335 srv.request.ode_config.sor_pgs_iters = config.sor_pgs_iters ;
2336 srv.request.ode_config.sor_pgs_rms_error_tol = config.sor_pgs_rms_error_tol ;
2337 srv.request.ode_config.sor_pgs_w = config.sor_pgs_w ;
2338 srv.request.ode_config.contact_surface_layer = config.contact_surface_layer ;
2339 srv.request.ode_config.contact_max_correcting_vel = config.contact_max_correcting_vel ;
2340 srv.request.ode_config.cfm = config.cfm ;
2341 srv.request.ode_config.erp = config.erp ;
2342 srv.request.ode_config.max_contacts = config.max_contacts ;
2344 ROS_INFO_NAMED(
"api_plugin",
"physics dynamics reconfigure update complete");
2346 ROS_INFO_NAMED(
"api_plugin",
"physics dynamics reconfigure complete");
2357 physics_reconfigure_get_client_.waitForExistence();
2364 ROS_INFO_NAMED(
"api_plugin",
"Physics dynamic reconfigure ready.");
2373 std::string open_bracket(
"<?");
2374 std::string close_bracket(
"?>");
2375 size_t pos1 = model_xml.find(open_bracket,0);
2376 size_t pos2 = model_xml.find(close_bracket,0);
2377 if (pos1 != std::string::npos && pos2 != std::string::npos)
2378 model_xml.replace(pos1,pos2-pos1+2,std::string(
""));
2382 const std::string &model_name,
2383 const ignition::math::Vector3d &initial_xyz,
2384 const ignition::math::Quaterniond &initial_q)
2389 TiXmlElement* pose_element;
2392 TiXmlElement* gazebo_tixml = gazebo_model_xml.FirstChildElement(
"sdf");
2395 ROS_WARN_NAMED(
"api_plugin",
"Could not find <sdf> element in sdf, so name and initial position cannot be applied");
2400 TiXmlElement* model_tixml = gazebo_tixml->FirstChildElement(
"model");
2404 if (model_tixml->Attribute(
"name") != NULL)
2407 model_tixml->RemoveAttribute(
"name");
2410 model_tixml->SetAttribute(
"name",model_name);
2415 TiXmlElement* world_tixml = gazebo_tixml->FirstChildElement(
"world");
2418 ROS_WARN_NAMED(
"api_plugin",
"Could not find <model> or <world> element in sdf, so name and initial position cannot be applied");
2422 model_tixml = world_tixml->FirstChildElement(
"include");
2425 ROS_WARN_NAMED(
"api_plugin",
"Could not find <include> element in sdf, so name and initial position cannot be applied");
2430 TiXmlElement* name_tixml = model_tixml->FirstChildElement(
"name");
2434 name_tixml =
new TiXmlElement(
"name");
2435 model_tixml->LinkEndChild(name_tixml);
2439 TiXmlText* text =
new TiXmlText(model_name);
2440 name_tixml->LinkEndChild( text );
2445 pose_element = model_tixml->FirstChildElement(
"pose");
2446 ignition::math::Pose3d model_pose;
2453 model_pose = this->
parsePose(pose_element->GetText());
2454 model_tixml->RemoveChild(pose_element);
2460 ignition::math::Pose3d new_model_pose = model_pose + ignition::math::Pose3d(initial_xyz, initial_q);
2463 std::ostringstream pose_stream;
2464 ignition::math::Vector3d model_rpy = new_model_pose.Rot().Euler();
2465 pose_stream << new_model_pose.Pos().X() <<
" " << new_model_pose.Pos().Y() <<
" " << new_model_pose.Pos().Z() <<
" " 2466 << model_rpy.X() <<
" " << model_rpy.Y() <<
" " << model_rpy.Z();
2469 TiXmlText* text =
new TiXmlText(pose_stream.str());
2470 TiXmlElement* new_pose_element =
new TiXmlElement(
"pose");
2471 new_pose_element->LinkEndChild(text);
2472 model_tixml->LinkEndChild(new_pose_element);
2478 std::vector<std::string> pieces;
2479 std::vector<double> vals;
2481 boost::split(pieces, str, boost::is_any_of(
" "));
2482 for (
unsigned int i = 0; i < pieces.size(); ++i)
2484 if (pieces[i] !=
"")
2488 vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
2490 catch(boost::bad_lexical_cast &e)
2492 sdferr <<
"xml key [" << str
2493 <<
"][" << i <<
"] value [" << pieces[i]
2494 <<
"] is not a valid double from a 3-tuple\n";
2495 return ignition::math::Pose3d();
2500 if (vals.size() == 6)
2501 return ignition::math::Pose3d(vals[0], vals[1], vals[2], vals[3], vals[4], vals[5]);
2504 ROS_ERROR_NAMED(
"api_plugin",
"Beware: failed to parse string [%s] as ignition::math::Pose3d, returning zeros.", str.c_str());
2505 return ignition::math::Pose3d();
2511 std::vector<std::string> pieces;
2512 std::vector<double> vals;
2514 boost::split(pieces, str, boost::is_any_of(
" "));
2515 for (
unsigned int i = 0; i < pieces.size(); ++i)
2517 if (pieces[i] !=
"")
2521 vals.push_back(boost::lexical_cast<double>(pieces[i].c_str()));
2523 catch(boost::bad_lexical_cast &e)
2525 sdferr <<
"xml key [" << str
2526 <<
"][" << i <<
"] value [" << pieces[i]
2527 <<
"] is not a valid double from a 3-tuple\n";
2528 return ignition::math::Vector3d();
2533 if (vals.size() == 3)
2534 return ignition::math::Vector3d(vals[0], vals[1], vals[2]);
2537 ROS_ERROR_NAMED(
"api_plugin",
"Beware: failed to parse string [%s] as ignition::math::Vector3d, returning zeros.", str.c_str());
2538 return ignition::math::Vector3d();
2543 const ignition::math::Vector3d &initial_xyz,
2544 const ignition::math::Quaterniond &initial_q)
2546 TiXmlElement* model_tixml = (gazebo_model_xml.FirstChildElement(
"robot"));
2551 TiXmlElement* origin_key = model_tixml->FirstChildElement(
"origin");
2555 origin_key =
new TiXmlElement(
"origin");
2556 model_tixml->LinkEndChild(origin_key);
2559 ignition::math::Vector3d xyz;
2560 ignition::math::Vector3d rpy;
2561 if (origin_key->Attribute(
"xyz"))
2563 xyz = this->
parseVector3(origin_key->Attribute(
"xyz"));
2564 origin_key->RemoveAttribute(
"xyz");
2566 if (origin_key->Attribute(
"rpy"))
2568 rpy = this->
parseVector3(origin_key->Attribute(
"rpy"));
2569 origin_key->RemoveAttribute(
"rpy");
2573 ignition::math::Pose3d model_pose = ignition::math::Pose3d(xyz, ignition::math::Quaterniond(rpy))
2574 + ignition::math::Pose3d(initial_xyz, initial_q);
2576 std::ostringstream xyz_stream;
2577 xyz_stream << model_pose.Pos().X() <<
" " << model_pose.Pos().Y() <<
" " << model_pose.Pos().Z();
2579 std::ostringstream rpy_stream;
2580 ignition::math::Vector3d model_rpy = model_pose.Rot().Euler();
2581 rpy_stream << model_rpy.X() <<
" " << model_rpy.Y() <<
" " << model_rpy.Z();
2583 origin_key->SetAttribute(
"xyz",xyz_stream.str());
2584 origin_key->SetAttribute(
"rpy",rpy_stream.str());
2587 ROS_WARN_NAMED(
"api_plugin",
"Could not find <model> element in sdf, so name and initial position is not applied");
2592 TiXmlElement* model_tixml = gazebo_model_xml.FirstChildElement(
"robot");
2596 if (model_tixml->Attribute(
"name") != NULL)
2599 model_tixml->RemoveAttribute(
"name");
2602 model_tixml->SetAttribute(
"name",model_name);
2605 ROS_WARN_NAMED(
"api_plugin",
"Could not find <robot> element in URDF, name not replaced");
2610 TiXmlNode* child = 0;
2611 child = model_xml->IterateChildren(child);
2612 while (child != NULL)
2614 if (child->Type() == TiXmlNode::TINYXML_ELEMENT &&
2615 child->ValueStr().compare(std::string(
"plugin")) == 0)
2617 if (child->FirstChildElement(
"robotNamespace") == NULL)
2619 TiXmlElement* child_elem = child->ToElement()->FirstChildElement(
"robotNamespace");
2622 child->ToElement()->RemoveChild(child_elem);
2623 child_elem = child->ToElement()->FirstChildElement(
"robotNamespace");
2625 TiXmlElement* key =
new TiXmlElement(
"robotNamespace");
2627 key->LinkEndChild(val);
2628 child->ToElement()->LinkEndChild(key);
2632 child = model_xml->IterateChildren(child);
2637 gazebo_msgs::SpawnModel::Response &res)
2639 std::string entity_type = gazebo_model_xml.RootElement()->FirstChild()->Value();
2641 std::transform(entity_type.begin(), entity_type.end(), entity_type.begin(), ::tolower);
2643 bool isLight = (entity_type ==
"light");
2646 std::ostringstream stream;
2647 stream << gazebo_model_xml;
2648 std::string gazebo_model_xml_string = stream.str();
2649 ROS_DEBUG_NAMED(
"api_plugin.xml",
"Gazebo Model XML\n\n%s\n\n ",gazebo_model_xml_string.c_str());
2652 gazebo::msgs::Factory msg;
2653 gazebo::msgs::Init(msg,
"spawn_model");
2654 msg.set_sdf( gazebo_model_xml_string );
2660 gazebo::msgs::Request *entity_info_msg = gazebo::msgs::CreateRequest(
"entity_info", model_name);
2662 delete entity_info_msg;
2665 #if GAZEBO_MAJOR_VERSION >= 8 2666 gazebo::physics::ModelPtr model =
world_->ModelByName(model_name);
2667 gazebo::physics::LightPtr light =
world_->LightByName(model_name);
2669 gazebo::physics::ModelPtr model =
world_->GetModel(model_name);
2670 gazebo::physics::LightPtr light =
world_->Light(model_name);
2672 if ((isLight && light != NULL) || (model != NULL))
2674 ROS_ERROR_NAMED(
"api_plugin",
"SpawnModel: Failure - model name %s already exist.",model_name.c_str());
2675 res.success =
false;
2676 res.status_message =
"SpawnModel: Failure - entity already exists.";
2685 sdf_light.SetFromString(gazebo_model_xml_string);
2686 gazebo::msgs::Light msg = gazebo::msgs::LightFromSDF(sdf_light.Root()->GetElement(
"light"));
2687 msg.set_name(model_name);
2706 res.success =
false;
2707 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;
2713 #if GAZEBO_MAJOR_VERSION >= 8 2714 if ((isLight &&
world_->LightByName(model_name) != NULL)
2715 || (
world_->ModelByName(model_name) != NULL))
2717 if ((isLight &&
world_->Light(model_name) != NULL)
2718 || (
world_->GetModel(model_name) != NULL))
2724 <<
" for entity " << model_name <<
" to spawn");
2726 std::this_thread::sleep_for(std::chrono::microseconds(2000));
2731 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()
Callback for a subscriber disconnecting from LinkStates ros topic.
ros::Publisher pub_performance_metrics_
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_
#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()
Callback for a subscriber connecting to LinkStates ros topic.
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()
Callback for a subscriber connecting to ModelStates ros topic.
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_
void publish(const boost::shared_ptr< M > &message) const
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_
void publishSimTime()
Callback to WorldUpdateBegin that publishes /clock. If pub_clock_frequency_ <= 0 (default behavior)...
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_
int pub_performance_metrics_connection_count_
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)
gazebo::transport::SubscriberPtr performance_metric_sub_
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()
Callback for a subscriber disconnecting from ModelStates ros topic.
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_