|
| std::map< std::string, sim::Entity > | GetEnabledJoints (const sim::Entity &_entity, sim::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.
|
| |
|
|
sim::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< controller_manager::ControllerManager > | controller_manager_ {nullptr} |
| | Controller manager.
|
| |
| rclcpp::Time | last_update_sim_time_ros_ |
| | Last time the update method was called.
|
| |
|
sim::EntityComponentManager * | ecm {nullptr} |
| | ECM pointer.
|
| |
|
int | update_rate |
| | controller update rate
|
| |
◆ GetEnabledJoints()
| std::map< std::string, sim::Entity > gz_ros2_control::GazeboSimROS2ControlPluginPrivate::GetEnabledJoints |
( |
const sim::Entity & |
_entity, |
|
|
sim::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 | Gazebo Entity Component Manager |
- Returns
- List of entities containing all enabled joints
◆ last_update_sim_time_ros_
| rclcpp::Time gz_ros2_control::GazeboSimROS2ControlPluginPrivate::last_update_sim_time_ros_ |
Initial value:=
rclcpp::Time(static_cast<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/gz_ros2_control/src/gz_ros2_control_plugin.cpp