Skip to content

Commit

Permalink
[MSA] Generate More New Launch Files (#1213)
Browse files Browse the repository at this point in the history
  • Loading branch information
DLu authored May 10, 2022
1 parent ceee5c2 commit f12f156
Show file tree
Hide file tree
Showing 14 changed files with 13 additions and 354 deletions.
13 changes: 13 additions & 0 deletions moveit_setup_assistant/moveit_setup_app_plugins/src/launches.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,19 @@ void Launches::onInit()
"moveit_rviz", { "rviz2", "rviz_common", "rviz_default_plugins", "moveit_ros_visualization" }));
available_launch_bundles_.back().addFile(
"config/moveit.rviz", "Configuration file for Rviz with the Motion Planning Plugin already setup.");
available_launch_bundles_.push_back(LaunchBundle(
"MoveGroup Launch", "Launch file to run the main MoveIt executable that provides the MoveGroup action",
"move_group", { "moveit_ros_move_group" }));
available_launch_bundles_.push_back(LaunchBundle("Static TF Launch",
"Launch file to broadcast static TF for the robot's virtual joints.",
"static_virtual_joint_tfs", { "tf2_ros" }));
available_launch_bundles_.push_back(LaunchBundle("Spawn Controllers Launch",
"Launch file to spawn the necessary controllers",
"spawn_controllers", { "controller_manager" }));
available_launch_bundles_.push_back(LaunchBundle("Demo Launch",
"Launch file to run a demo of MoveGroup. Warning that it requires "
"the above launch files to all be generated as well.",
"demo"));

available_launch_bundles_.push_back(LaunchBundle("Setup Assistant Launch",
"Launch file for easily re-starting the MoveIt "
Expand Down
10 changes: 0 additions & 10 deletions moveit_setup_assistant/moveit_setup_framework/src/srdf_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,16 +198,6 @@ void SRDFConfig::collectVariables(std::vector<TemplateVariable>& variables)
variables.push_back(TemplateVariable("ROBOT_NAME", srdf_.robot_name_));
variables.push_back(TemplateVariable("ROBOT_ROOT_LINK", robot_model_->getRootLinkName()));
variables.push_back(TemplateVariable("PLANNING_FRAME", robot_model_->getModelFrame()));

std::stringstream vjb;
unsigned int counter = 0;
for (const auto& vj : srdf_.virtual_joints_)
{
vjb << " <node pkg=\"tf2_ros\" type=\"static_transform_publisher\" name=\"virtual_joint_broadcaster_" << counter
<< "\" args=\"0 0 0 0 0 0 " << vj.parent_frame_ << " " << vj.child_link_ << "\" />" << std::endl;
counter++;
}
variables.push_back(TemplateVariable("VIRTUAL_JOINT_BROADCASTER", vjb.str()));
}

} // namespace moveit_setup_framework
Expand Down

This file was deleted.

68 changes: 0 additions & 68 deletions moveit_setup_assistant/old_assistant/templates/launch/demo.launch

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

This file was deleted.

0 comments on commit f12f156

Please sign in to comment.