-
Notifications
You must be signed in to change notification settings - Fork 773
ROS 2 Migration: gazebo_ros_utils
chapulina edited this page Aug 30, 2018
·
1 revision
The gazebo_ros_utils.h
header has been deprecated on ROS 2. This guide explains how to migrate.
- Description: Access model name from sensor
TODO
-
Description: Get the value of the
<robotNamespace>
SDF tag; if none, get the model name from the sensor usingGetModelName
.
TODO
-
Description: Get a pointer to a
ros::NodeHandle
. -
Replacement: Get a pointer to an
rclcpp::Node
withgazebo_ros::Node::Get()
.
TODO
TODO
TODO
- Description: Get a boolean value from an SDF tag.
-
Replacement: Use
sdf::Element::Get<bool>()
ROS 1
PluginName::Load(gazebo::physics::ModelPtr & _model, sdf::Element _sdf)
{
auto gazebo_ros = GazeboRosPtr(new GazeboRos(_model, _sdf, "PluginName"));
bool do_smth = false;
gazebo_ros->getParameterBoolean(do_smth, "do_smth", false);
}
ROS 2
PluginName::Load(gazebo::physics::ModelPtr & _model, sdf::Element _sdf)
{
bool do_smth = _sdf->Get<bool>("do_smth", false).first;
}
- Description: Get any value from an SDF tag.
-
Replacement: Use
sdf::Element::Get<T>()
ROS 1
PluginName::Load(gazebo::physics::ModelPtr & _model, sdf::Element _sdf)
{
auto gazebo_ros = GazeboRosPtr(new GazeboRos(_model, _sdf, "PluginName"));
std::string some_string = false;
gazebo_ros->getParameter<std::string>(some_string, "some_string", "default_value");
}
ROS 2
PluginName::Load(gazebo::physics::ModelPtr & _model, sdf::Element _sdf)
{
std::string some_string = _sdf->Get<std::string>("some_string", "default_value").first;
}
- Description: Get a joint based on an SDF tag.
-
Replacement: Use
sdf::Element::Get<std::string>()
andgazebo::physics::Model::GetJoint()
ROS 1
PluginName::Load(gazebo::physics::ModelPtr & _model, sdf::Element _sdf)
{
auto gazebo_ros = GazeboRosPtr(new GazeboRos(_model, _sdf, "PluginName"));
gazebo::physics::JointPtr joint = gazebo_ros->getJoint(_model, "joint_name", "default_value");
}
ROS 2
PluginName::Load(gazebo::physics::ModelPtr & _model, sdf::Element _sdf)
{
std::string joint_name = _sdf->Get<std::string>("joint_name", "default_value").first;
gazebo::physics::JointPtr joint = _model->GetJoint(joint_name);
}