|
std::string | getURDF () const |
| Get the URDF XML from the parameter server.
|
|
std::map< std::string, ignition::gazebo::Entity > | GetEnabledJoints (const ignition::gazebo::Entity &_entity, ignition::gazebo::EntityComponentManager &_ecm) const |
| Get a list of enabled, unique, 1-axis joints of the model. If no joint names are specified in the plugin configuration, all valid 1-axis joints are returned.
|
|
|
ignition::gazebo::Entity | entity_ |
| Entity ID for sensor within Gazebo.
|
|
std::shared_ptr< rclcpp::Node > | node_ {nullptr} |
| Node Handles.
|
|
std::thread | thread_executor_spin_ |
| Thread where the executor will spin.
|
|
rclcpp::executors::MultiThreadedExecutor::SharedPtr | executor_ |
| Executor to spin the controller.
|
|
rclcpp::Duration | control_period_ = rclcpp::Duration(1, 0) |
| Timing.
|
|
std::shared_ptr< pluginlib::ClassLoader< ign_ros2_control::IgnitionSystemInterface > > | robot_hw_sim_loader_ {nullptr} |
| Interface loader.
|
|
std::shared_ptr< controller_manager::ControllerManager > | controller_manager_ {nullptr} |
| Controller manager.
|
|
std::string | robot_description_ = "robot_description" |
| String with the robot description param_name.
|
|
std::string | robot_description_node_ = "robot_state_publisher" |
| String with the name of the node that contains the robot_description.
|
|
rclcpp::Time | last_update_sim_time_ros_ |
| Last time the update method was called.
|
|
ignition::gazebo::EntityComponentManager * | ecm {nullptr} |
| ECM pointer.
|
|
int | update_rate |
| controller update rate
|
|
◆ GetEnabledJoints()
std::map< std::string, ignition::gazebo::Entity > ign_ros2_control::IgnitionROS2ControlPluginPrivate::GetEnabledJoints |
( |
const ignition::gazebo::Entity & |
_entity, |
|
|
ignition::gazebo::EntityComponentManager & |
_ecm |
|
) |
| const |
Get a list of enabled, unique, 1-axis joints of the model. If no joint names are specified in the plugin configuration, all valid 1-axis joints are returned.
- Parameters
-
[in] | _entity | Entity of the model that the plugin is being configured for |
[in] | _ecm | Ignition Entity Component Manager |
- Returns
- List of entities containing all enabled joints
◆ last_update_sim_time_ros_
rclcpp::Time ign_ros2_control::IgnitionROS2ControlPluginPrivate::last_update_sim_time_ros_ |
Initial value:=
rclcpp::Time((int64_t)0, RCL_ROS_TIME)
Last time the update method was called.
The documentation for this class was generated from the following file:
- gz_ros2_control/ign_ros2_control/src/ign_ros2_control_plugin.cpp