Skip to content

Commit

Permalink
[MSA] Add Setup Step for Generating Launch Files (#1129)
Browse files Browse the repository at this point in the history
* Change to polling method for determining dependencies

* Add Setup Step for Generating Launch Files

* Generate basic launch files using moveit_configs_utils

* Some documentation!
  • Loading branch information
DLu committed Mar 24, 2022
1 parent 262c9af commit 9a8e005
Show file tree
Hide file tree
Showing 26 changed files with 875 additions and 265 deletions.
45 changes: 0 additions & 45 deletions moveit_setup_assistant/extra_generated_files_code.txt
Original file line number Diff line number Diff line change
Expand Up @@ -92,13 +92,6 @@
"SRDF, joints_limits.yaml file, ompl_planning.yaml file, optionally the URDF, etc";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);

// moveit_rviz.launch --------------------------------------------------------------------------------------
file.file_name_ = "moveit_rviz.launch";
file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
file.description_ = "Visualize in Rviz the robot's planning groups running with interactive markers that allow goal "
"states to be set.";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);

// ompl_planning_pipeline.launch
// --------------------------------------------------------------------------------------
Expand Down Expand Up @@ -137,26 +130,6 @@
file.description_ = "Helper launch file that can choose between different planning pipelines to be loaded.";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);

// warehouse_settings.launch --------------------------------------------------------------------------------------
file.file_name_ = "warehouse_settings.launch.xml";
file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
file.description_ = "Helper launch file that specifies default settings for MongoDB.";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);

// warehouse.launch --------------------------------------------------------------------------------------
file.file_name_ = "warehouse.launch";
file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
file.description_ = "Launch file for starting MongoDB.";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);

// default_warehouse_db.launch --------------------------------------------------------------------------------------
file.file_name_ = "default_warehouse_db.launch";
file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
file.description_ = "Launch file for starting the warehouse with a default MongoDB.";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);

// run_benchmark_ompl.launch --------------------------------------------------------------------------------------
file.file_name_ = "run_benchmark_ompl.launch";
Expand Down Expand Up @@ -234,28 +207,10 @@
file.description_ = "Control the Rviz Motion Planning Plugin with a joystick";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);

// setup_assistant.launch ------------------------------------------------------------------
file.file_name_ = "setup_assistant.launch";
file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
template_path = config_data_->appendPaths(
template_launch_path, "edit_configuration_package.launch"); // named this so that this launch file is not mixed
// up with the SA's real launch file
file.description_ = "Launch file for easily re-starting the MoveIt Setup Assistant to edit this robot's generated "
"configuration package.";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);

// ros_controllers.launch ------------------------------------------------------------------
file.file_name_ = "ros_controllers.launch";
file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
template_path = config_data_->appendPaths(template_launch_path, "ros_controllers.launch");
file.description_ = "ros_controllers launch file";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);
file.write_on_changes = MoveItConfigData::GROUPS;

// moveit.rviz ------------------------------------------------------------------
file.file_name_ = "moveit.rviz";
file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
template_path = config_data_->appendPaths(template_launch_path, "moveit.rviz");
file.description_ = "Configuration file for Rviz with the Motion Planning Plugin already setup. Used by passing "
"roslaunch moveit_rviz.launch config:=true";
file.gen_func_ = std::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, std::placeholders::_1);
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,14 @@ set(CMAKE_AUTOMOC ON)
add_definitions(-DQT_NO_KEYWORDS)

qt5_wrap_cpp(MOC_FILES
include/moveit_setup_app_plugins/launches_widget.hpp
include/moveit_setup_app_plugins/perception_widget.hpp
)

add_library(${PROJECT_NAME}
src/launches.cpp
src/launches_widget.cpp
src/launches_config.cpp
src/perception_config.cpp
src/perception.cpp
src/perception_widget.cpp
Expand All @@ -44,6 +48,8 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()

install(DIRECTORY templates DESTINATION share/${PROJECT_NAME})

install(TARGETS ${PROJECT_NAME}
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,217 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2022, Metro Robots
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Metro Robots nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: David V. Lu!! */
#pragma once

#include <moveit_setup_framework/templates.hpp>
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <moveit_setup_framework/utilities.hpp>

namespace moveit_setup_app_plugins
{
using moveit_setup_framework::appendPaths;

/**
* @brief One launch file and any other bonus files that get bundled with it, i.e. the RViz launch file and its config.
*
* Each launch bundle is presented to the user as option to generate. They are bundled because it would not (generally)
* make sense to generate the RViz config without the launch file.
*/
class LaunchBundle
{
public:
/**
* @param title The display name for this LaunchBundle
* @param description An English description of the files contained within
* @param launch_name The identifier that signifies the name of the generated launch file (launch_name.launch.py)
* @param dependencies Each string is the name of a package that should be added as a dependency if this bundle is generated
*/
LaunchBundle(const std::string& title, const std::string& description, const std::string& launch_name,
const std::set<std::string>& dependencies = {})
: title_(title), description_(description), launch_name_(launch_name), dependencies_(dependencies), id_(-1)
{
}

const std::string& getTitle() const
{
return title_;
}

const std::string& getDescription() const
{
return description_;
}

/**
* @brief The ID is an index in a list, used for quick identification and argument passing
*/
unsigned int getID() const
{
return id_;
}

void setID(unsigned int id)
{
id_ = id;
}

void addFile(const std::string& relative_path, const std::string& description)
{
bonus_files_.push_back(BonusFile(relative_path, description));
}

const std::set<std::string> getDependencies() const
{
return dependencies_;
}

/**
* @brief Defined so that LaunchBundles can be added to sets
*/
bool operator<(const LaunchBundle& other) const
{
return title_ < other.title_;
}

class GenericLaunchTemplate : public moveit_setup_framework::TemplatedGeneratedFile
{
public:
GenericLaunchTemplate(const std::string& package_path, const std::time_t& last_gen_time, const LaunchBundle& parent)
: TemplatedGeneratedFile(package_path, last_gen_time), parent_(parent)
{
function_name_ = "generate_" + parent_.launch_name_ + "_launch";
relative_path_ = appendPaths("launch", parent_.launch_name_ + ".launch.py");
template_path_ = appendPaths(ament_index_cpp::get_package_share_directory("moveit_setup_app_plugins"),
"templates/launch/generic.launch.py.template");
}

std::string getRelativePath() const override
{
return relative_path_;
}

std::string getDescription() const override
{
return parent_.description_;
}

std::string getTemplatePath() const override
{
return template_path_;
}

bool hasChanges() const override
{
return false;
}

bool write() override
{
// Add function name as a TemplateVariable, then remove it
variables_.push_back(moveit_setup_framework::TemplateVariable("FUNCTION_NAME", function_name_));
bool ret = TemplatedGeneratedFile::write();
variables_.pop_back();
return ret;
}

protected:
const LaunchBundle& parent_;
std::string function_name_, relative_path_, template_path_;
};

struct BonusFile // basically a std::pair<std::string, std::string>
{
BonusFile(const std::string& path, const std::string& description) : path(path), description(description)
{
}
std::string path;
std::string description;
};

class BonusTemplatedFile : public moveit_setup_framework::TemplatedGeneratedFile
{
public:
BonusTemplatedFile(const std::string& package_path, const std::time_t& last_gen_time,
const std::string& relative_path, const std::string& description)
: TemplatedGeneratedFile(package_path, last_gen_time), relative_path_(relative_path), description_(description)
{
}

std::string getRelativePath() const override
{
return relative_path_;
}

std::string getDescription() const override
{
return description_;
}

std::string getTemplatePath() const override
{
return appendPaths(appendPaths(ament_index_cpp::get_package_share_directory("moveit_setup_app_plugins"),
"templates"),
relative_path_);
}

bool hasChanges() const override
{
return false;
}

protected:
std::string relative_path_, description_;
};

void collectFiles(const std::string& package_path, const std::time_t& last_gen_time,
std::vector<moveit_setup_framework::GeneratedFilePtr>& files) const
{
files.push_back(std::make_shared<GenericLaunchTemplate>(package_path, last_gen_time, *this));

for (const BonusFile& bonus_file : bonus_files_)
{
files.push_back(
std::make_shared<BonusTemplatedFile>(package_path, last_gen_time, bonus_file.path, bonus_file.description));
}
}

protected:
std::string title_, description_, launch_name_;
std::set<std::string> dependencies_;
unsigned int id_;

std::vector<BonusFile> bonus_files_;
};
} // namespace moveit_setup_app_plugins
Loading

0 comments on commit 9a8e005

Please sign in to comment.