moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Classes | Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
moveit_setup::app::PerceptionConfig Class Reference

#include <perception_config.hpp>

Inheritance diagram for moveit_setup::app::PerceptionConfig:
Inheritance graph
[legend]
Collaboration diagram for moveit_setup::app::PerceptionConfig:
Collaboration graph
[legend]

Classes

class  GeneratedSensorConfig
 

Public Member Functions

void loadPrevious (const std::filesystem::path &package_path, const YAML::Node &node) override
 Loads the configuration from an existing MoveIt configuration.
 
bool isConfigured () const override
 Return true if this part of the configuration is completely set up.
 
const std::vector< SensorParameters > & getSensorPluginConfig ()
 Used for adding a sensor plugin configuration parameter to the sensor plugin configuration parameter list.
 
void clearSensorPluginConfig ()
 Clear the sensor plugin configuration parameter list.
 
void setConfig (const SensorParameters &parameters)
 
void collectFiles (const std::filesystem::path &package_path, const GeneratedTime &last_gen_time, std::vector< GeneratedFilePtr > &files) override
 Collect the files generated by this configuration and add them to the vector.
 
- Public Member Functions inherited from moveit_setup::SetupConfig
 SetupConfig ()=default
 
 SetupConfig (const SetupConfig &)=default
 
 SetupConfig (SetupConfig &&)=default
 
SetupConfigoperator= (const SetupConfig &)=default
 
SetupConfigoperator= (SetupConfig &&)=default
 
virtual ~SetupConfig ()=default
 
void initialize (const std::shared_ptr< DataWarehouse > &config_data, const rclcpp::Node::SharedPtr &parent_node, const std::string &name)
 Called after construction to initialize the step.
 
virtual void onInit ()
 Overridable initialization method.
 
const std::string & getName ()
 The name for this part of the configuration.
 
virtual YAML::Node saveToYaml () const
 Optionally save "meta" information for saving in the .setup_assistant yaml file.
 
virtual void collectDependencies (std::set< std::string > &) const
 Collect the package dependencies generated by this configuration.
 
virtual void collectVariables (std::vector< TemplateVariable > &)
 Collect key/value pairs for use in templates.
 

Static Public Member Functions

static std::vector< SensorParametersload3DSensorsYAML (const std::filesystem::path &file_path)
 Load perception sensor config.
 

Protected Attributes

std::vector< SensorParameterssensors_plugin_config_parameter_list_
 Sensor plugin configuration parameter list, each sensor plugin type is a map of string pairs.
 
bool changed_ { false }
 
- Protected Attributes inherited from moveit_setup::SetupConfig
std::shared_ptr< DataWarehouseconfig_data_
 
rclcpp::Node::SharedPtr parent_node_
 
std::string name_
 
std::shared_ptr< rclcpp::Logger > logger_
 

Detailed Description

Definition at line 47 of file perception_config.hpp.

Member Function Documentation

◆ clearSensorPluginConfig()

void moveit_setup::app::PerceptionConfig::clearSensorPluginConfig ( )

Clear the sensor plugin configuration parameter list.

Definition at line 118 of file perception_config.cpp.

◆ collectFiles()

void moveit_setup::app::PerceptionConfig::collectFiles ( const std::filesystem::path &  ,
const GeneratedTime ,
std::vector< GeneratedFilePtr > &   
)
inlineoverridevirtual

Collect the files generated by this configuration and add them to the vector.

Parameters
[in]package_paththe path to the root of the config package
[in]last_gen_timeThe time (if any) when the config package was last generated
[out]filesWhere to put the new generated files

Reimplemented from moveit_setup::SetupConfig.

Definition at line 105 of file perception_config.hpp.

◆ getSensorPluginConfig()

const std::vector< SensorParameters > & moveit_setup::app::PerceptionConfig::getSensorPluginConfig ( )
inline

Used for adding a sensor plugin configuration parameter to the sensor plugin configuration parameter list.

Definition at line 63 of file perception_config.hpp.

◆ isConfigured()

bool moveit_setup::app::PerceptionConfig::isConfigured ( ) const
inlineoverridevirtual

Return true if this part of the configuration is completely set up.

Reimplemented from moveit_setup::SetupConfig.

Definition at line 55 of file perception_config.hpp.

◆ load3DSensorsYAML()

std::vector< SensorParameters > moveit_setup::app::PerceptionConfig::load3DSensorsYAML ( const std::filesystem::path &  file_path)
static

Load perception sensor config.

Definition at line 67 of file perception_config.cpp.

Here is the caller graph for this function:

◆ loadPrevious()

void moveit_setup::app::PerceptionConfig::loadPrevious ( const std::filesystem::path &  ,
const YAML::Node &   
)
overridevirtual

Loads the configuration from an existing MoveIt configuration.

The data can be loaded directly from files in the configuration via the package path.

Certain other pieces of "meta" information may be stored in the .setup_assistant yaml file in the root of the configuration. If there is a node in that file that matches this config's name, it is passed in as an argument.

Parameters
package_pathThe path to the root folder of the configuration.

Reimplemented from moveit_setup::SetupConfig.

Definition at line 46 of file perception_config.cpp.

Here is the call graph for this function:

◆ setConfig()

void moveit_setup::app::PerceptionConfig::setConfig ( const SensorParameters parameters)

Definition at line 131 of file perception_config.cpp.

Member Data Documentation

◆ changed_

bool moveit_setup::app::PerceptionConfig::changed_ { false }
protected

Definition at line 114 of file perception_config.hpp.

◆ sensors_plugin_config_parameter_list_

std::vector<SensorParameters> moveit_setup::app::PerceptionConfig::sensors_plugin_config_parameter_list_
protected

Sensor plugin configuration parameter list, each sensor plugin type is a map of string pairs.

Definition at line 113 of file perception_config.hpp.


The documentation for this class was generated from the following files: