Skip to content

Commit

Permalink
remove useless comments
Browse files Browse the repository at this point in the history
  • Loading branch information
sp-sophia-labs committed Nov 4, 2022
1 parent b38cb33 commit 1918fd1
Showing 1 changed file with 1 addition and 12 deletions.
13 changes: 1 addition & 12 deletions ign_ros2_control/src/ign_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,6 @@ void IgnitionROS2ControlPlugin::Configure(
ignition::gazebo::EntityComponentManager & _ecm,
ignition::gazebo::EventManager &)
{

// Make sure the controller is attached to a valid model
const auto model = ignition::gazebo::Model(_entity);
if (!model.Valid(_ecm)) {
Expand All @@ -267,7 +266,6 @@ void IgnitionROS2ControlPlugin::Configure(
}

// Get params from SDF
// TODO check if this is used. This used to be passed to the default context
std::string paramFileName = _sdf->Get<std::string>("parameters");
std::vector<std::string> arguments = {"--ros-args", "--params-file", paramFileName};

Expand All @@ -294,19 +292,13 @@ void IgnitionROS2ControlPlugin::Configure(
if (ns.empty() || ns[0] != '/') {
ns = '/' + ns;
}
if(ns.length()>1) {
if (ns.length() > 1) {
this->dataPtr->robot_namespace_ = ns;
this->dataPtr->robot_description_node_ = ns + "/robot_state_publisher";

// TODO check if node names need to be prefixed
//ns.erase(0, 1); //removing '/' for node names
//this->dataPtr->robot_description_ = ns + "_robot_description";
//this->dataPtr->controller_manager_node_ = ns + "_controller_manager";
}
}

// Get list of remapping rules from SDF
// TODO check if this is used. This used to be passed to the default context
if (sdfRos->HasElement("remapping")) {
sdf::ElementPtr argument_sdf = sdfRos->GetElement("remapping");
arguments.push_back(RCL_ROS_ARGS_FLAG);
Expand All @@ -321,8 +313,6 @@ void IgnitionROS2ControlPlugin::Configure(


// Create a default context, if not already
// TODO this only triggers for the first robot launch,
// following robots will not see their params passed to the context
if (!rclcpp::ok()) {
rclcpp::init(static_cast<int>(argv.size()), argv.data());
}
Expand Down Expand Up @@ -356,7 +346,6 @@ void IgnitionROS2ControlPlugin::Configure(
return;
}


// Read urdf from ros parameter server then
// setup actuators and mechanism control node.
// This call will block if ROS is not properly initialized.
Expand Down

0 comments on commit 1918fd1

Please sign in to comment.