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

#include <simulation.hpp>

Inheritance diagram for moveit_setup::simulation::Simulation:
Inheritance graph
[legend]
Collaboration diagram for moveit_setup::simulation::Simulation:
Collaboration graph
[legend]

Public Member Functions

std::string getName () const override
 Returns the name of the setup step.
 
void onInit () override
 Overridable initialization method.
 
bool isReady () const override
 Return true if the data necessary to proceed with this step has been configured.
 
std::filesystem::path getURDFPath () const
 
std::string getURDFPackageName () const
 
std::string getURDFContents () const
 
std::string getJointHardwareInterface (const std::string &joint_name)
 Helper function to get the controller that is controlling the joint.
 
std::string getGazeboCompatibleURDF ()
 Parses the existing urdf and constructs a string from it with the elements required by gazebo simulator added.
 
bool outputGazeboURDFFile (const std::filesystem::path &file_path)
 
bool isValidXML (const std::string &new_urdf_contents, int &error_row, std::string &error_description) const
 Check if the given xml is valid.
 
- Public Member Functions inherited from moveit_setup::SetupStep
 SetupStep ()=default
 
 SetupStep (const SetupStep &)=default
 
 SetupStep (SetupStep &&)=default
 
SetupStepoperator= (const SetupStep &)=default
 
SetupStepoperator= (SetupStep &&)=default
 
virtual ~SetupStep ()=default
 
void initialize (const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data)
 Called after construction to initialize the step.
 
const rclcpp::Logger & getLogger () const
 Makes a namespaced logger for this step available to the widget.
 

Protected Attributes

std::shared_ptr< URDFConfigurdf_config_
 
std::string gazebo_urdf_string_
 Gazebo URDF robot model string.
 
bool save_gazebo_urdf_
 Whether a new Gazebo URDF is created.
 
- Protected Attributes inherited from moveit_setup::SetupStep
DataWarehousePtr config_data_
 
rclcpp::Node::SharedPtr parent_node_
 
std::shared_ptr< rclcpp::Logger > logger_
 

Detailed Description

Definition at line 45 of file simulation.hpp.

Member Function Documentation

◆ getGazeboCompatibleURDF()

std::string moveit_setup::simulation::Simulation::getGazeboCompatibleURDF ( )

Parses the existing urdf and constructs a string from it with the elements required by gazebo simulator added.

Returns
gazebo compatible urdf or empty if error encountered

Definition at line 85 of file simulation.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getJointHardwareInterface()

std::string moveit_setup::simulation::Simulation::getJointHardwareInterface ( const std::string &  joint_name)

Helper function to get the controller that is controlling the joint.

Returns
controller type

TODO: Need to port this - may require depending on moveit_setup_controllers ControllerConfig

for (ControllerConfig& ros_control_config : controller_configs_) { std::vector<std::string>::iterator joint_it = std::find(ros_control_config.joints_.begin(), ros_control_config.joints_.end(), joint_name); if (joint_it != ros_control_config.joints_.end()) { if (ros_control_config.type_.substr(0, 8) == "position") return "hardware_interface/PositionJointInterface"; else if (ros_control_config.type_.substr(0, 8) == "velocity") return "hardware_interface/VelocityJointInterface"; As of writing this, available joint command interfaces are position, velocity and effort. else return "hardware_interface/EffortJointInterface"; } }

Definition at line 51 of file simulation.cpp.

Here is the caller graph for this function:

◆ getName()

std::string moveit_setup::simulation::Simulation::getName ( ) const
inlineoverridevirtual

Returns the name of the setup step.

Implements moveit_setup::SetupStep.

Definition at line 48 of file simulation.hpp.

◆ getURDFContents()

std::string moveit_setup::simulation::Simulation::getURDFContents ( ) const
inline

Definition at line 70 of file simulation.hpp.

◆ getURDFPackageName()

std::string moveit_setup::simulation::Simulation::getURDFPackageName ( ) const
inline

Definition at line 65 of file simulation.hpp.

◆ getURDFPath()

std::filesystem::path moveit_setup::simulation::Simulation::getURDFPath ( ) const
inline

Definition at line 60 of file simulation.hpp.

Here is the caller graph for this function:

◆ isReady()

bool moveit_setup::simulation::Simulation::isReady ( ) const
inlineoverridevirtual

Return true if the data necessary to proceed with this step has been configured.

Reimplemented from moveit_setup::SetupStep.

Definition at line 55 of file simulation.hpp.

◆ isValidXML()

bool moveit_setup::simulation::Simulation::isValidXML ( const std::string &  new_urdf_contents,
int &  error_row,
std::string &  error_description 
) const

Check if the given xml is valid.

Parameters
[in]new_urdf_contentsThe string of xml to check
[out]error_rowThe row of the error
[out]error_descriptionThe description
Returns
True if valid, false otherwise

Definition at line 188 of file simulation.cpp.

Here is the caller graph for this function:

◆ onInit()

void moveit_setup::simulation::Simulation::onInit ( )
overridevirtual

Overridable initialization method.

Reimplemented from moveit_setup::SetupStep.

Definition at line 43 of file simulation.cpp.

◆ outputGazeboURDFFile()

bool moveit_setup::simulation::Simulation::outputGazeboURDFFile ( const std::filesystem::path &  file_path)

Definition at line 173 of file simulation.cpp.

Member Data Documentation

◆ gazebo_urdf_string_

std::string moveit_setup::simulation::Simulation::gazebo_urdf_string_
protected

Gazebo URDF robot model string.

Definition at line 104 of file simulation.hpp.

◆ save_gazebo_urdf_

bool moveit_setup::simulation::Simulation::save_gazebo_urdf_
protected

Whether a new Gazebo URDF is created.

Definition at line 107 of file simulation.hpp.

◆ urdf_config_

std::shared_ptr<URDFConfig> moveit_setup::simulation::Simulation::urdf_config_
protected

Definition at line 100 of file simulation.hpp.


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