moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <simulation.hpp>
Public Member Functions | |
std::string | getName () const override |
Returns the name of the setup step. More... | |
void | onInit () override |
Overridable initialization method. More... | |
bool | isReady () const override |
Return true if the data necessary to proceed with this step has been configured. More... | |
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. More... | |
std::string | getGazeboCompatibleURDF () |
Parses the existing urdf and constructs a string from it with the elements required by gazebo simulator added. More... | |
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. More... | |
Public Member Functions inherited from moveit_setup::SetupStep | |
SetupStep ()=default | |
SetupStep (const SetupStep &)=default | |
SetupStep (SetupStep &&)=default | |
SetupStep & | operator= (const SetupStep &)=default |
SetupStep & | operator= (SetupStep &&)=default |
virtual | ~SetupStep ()=default |
void | initialize (const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data) |
Called after construction to initialize the step. More... | |
const rclcpp::Logger & | getLogger () const |
Makes a namespaced logger for this step available to the widget. More... | |
Protected Attributes | |
std::shared_ptr< URDFConfig > | urdf_config_ |
std::string | gazebo_urdf_string_ |
Gazebo URDF robot model string. More... | |
bool | save_gazebo_urdf_ |
Whether a new Gazebo URDF is created. More... | |
Protected Attributes inherited from moveit_setup::SetupStep | |
DataWarehousePtr | config_data_ |
rclcpp::Node::SharedPtr | parent_node_ |
std::shared_ptr< rclcpp::Logger > | logger_ |
Definition at line 45 of file simulation.hpp.
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.
Definition at line 85 of file simulation.cpp.
std::string moveit_setup::simulation::Simulation::getJointHardwareInterface | ( | const std::string & | joint_name | ) |
Helper function to get the controller that is controlling the joint.
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.
|
inlineoverridevirtual |
Returns the name of the setup step.
Implements moveit_setup::SetupStep.
Definition at line 48 of file simulation.hpp.
|
inline |
Definition at line 70 of file simulation.hpp.
|
inline |
Definition at line 65 of file simulation.hpp.
|
inline |
|
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.
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.
[in] | new_urdf_contents | The string of xml to check |
[out] | error_row | The row of the error |
[out] | error_description | The description |
Definition at line 188 of file simulation.cpp.
|
overridevirtual |
Overridable initialization method.
Reimplemented from moveit_setup::SetupStep.
Definition at line 43 of file simulation.cpp.
bool moveit_setup::simulation::Simulation::outputGazeboURDFFile | ( | const std::filesystem::path & | file_path | ) |
Definition at line 173 of file simulation.cpp.
|
protected |
Gazebo URDF robot model string.
Definition at line 104 of file simulation.hpp.
|
protected |
Whether a new Gazebo URDF is created.
Definition at line 107 of file simulation.hpp.
|
protected |
Definition at line 100 of file simulation.hpp.