ros2_control - humble
Loading...
Searching...
No Matches
Public Attributes | List of all members
gazebo_ros2_control::GazeboSystemPrivate Class Reference

Public Attributes

size_t n_dof_
 Degrees od freedom.
 
size_t n_sensors_
 Number of sensors.
 
gazebo::physics::ModelPtr parent_model_
 Gazebo Model Ptr.
 
rclcpp::Time last_update_sim_time_ros_
 last time the write method was called.
 
std::vector< std::string > joint_names_
 vector with the joint's names.
 
std::vector< GazeboSystemInterface::ControlMethodjoint_control_methods_
 vector with the control method defined in the URDF for each joint.
 
std::vector< bool > is_joint_actuated_
 vector with indication for actuated joints (vs. passive joints)
 
std::vector< gazebo::physics::JointPtr > sim_joints_
 handles to the joints from within Gazebo
 
std::vector< double > joint_position_
 vector with the current joint position
 
std::vector< double > joint_velocity_
 vector with the current joint velocity
 
std::vector< double > joint_effort_
 vector with the current joint effort
 
std::vector< double > joint_position_cmd_
 vector with the current cmd joint position
 
std::vector< double > joint_velocity_cmd_
 vector with the current cmd joint velocity
 
std::vector< double > joint_effort_cmd_
 vector with the current cmd joint effort
 
std::vector< control_toolbox::Pidvel_pid
 Joint velocity PID utils.
 
std::vector< control_toolbox::Pidpos_pid
 Joint position PID utils.
 
std::vector< bool > is_pos_pid
 
std::vector< bool > is_vel_pid
 
std::vector< gazebo::sensors::ImuSensorPtr > sim_imu_sensors_
 handles to the imus from within Gazebo
 
std::vector< std::array< double, 10 > > imu_sensor_data_
 An array per IMU with 4 orientation, 3 angular velocity and 3 linear acceleration.
 
std::vector< gazebo::sensors::ForceTorqueSensorPtr > sim_ft_sensors_
 handles to the FT sensors from within Gazebo
 
std::vector< std::array< double, 6 > > ft_sensor_data_
 An array per FT sensor for 3D force and torquee.
 
std::vector< hardware_interface::StateInterfacestate_interfaces_
 state interfaces that will be exported to the Resource Manager
 
std::vector< hardware_interface::CommandInterfacecommand_interfaces_
 command interfaces that will be exported to the Resource Manager
 
std::vector< MimicJointmimic_joints_
 mapping of mimicked joints to index of joint they mimic
 
bool hold_joints_ = true
 
GazeboSystemInterface::ControlMethod_ position_control_method_
 
GazeboSystemInterface::ControlMethod_ velocity_control_method_
 

Member Data Documentation

◆ position_control_method_

GazeboSystemInterface::ControlMethod_ gazebo_ros2_control::GazeboSystemPrivate::position_control_method_
Initial value:
=
GazeboSystemInterface::ControlMethod_::POSITION

◆ velocity_control_method_

GazeboSystemInterface::ControlMethod_ gazebo_ros2_control::GazeboSystemPrivate::velocity_control_method_
Initial value:
=
GazeboSystemInterface::ControlMethod_::VELOCITY

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