#include <hebiros_gazebo_joint.h>

Public Member Functions | |
| HebirosGazeboJoint (const std::string &name, const std::string &model_name, bool is_x8, std::shared_ptr< ros::NodeHandle > n) | |
| bool | isX8 () const |
| void | SubIMU (const boost::shared_ptr< sensor_msgs::Imu const > data) |
Public Attributes | |
| geometry_msgs::Vector3 | accelerometer |
| int | command_index |
| double | effort_elapsed_error {} |
| double | effort_prev_error {} |
| int | feedback_index |
| double | gear_ratio {} |
| geometry_msgs::Vector3 | gyro |
| ros::Subscriber | imu_subscriber |
| double | low_pass_alpha {} |
| std::string | model_name |
| std::string | name |
| double | position_elapsed_error {} |
| double | position_prev_error {} |
| double | prev_force {} |
| hebiros::sim::TemperatureModel | temperature |
| hebiros::sim::TemperatureSafetyController | temperature_safety {155} |
| double | velocity_elapsed_error {} |
| double | velocity_prev_error {} |
Definition at line 9 of file hebiros_gazebo_joint.h.
| HebirosGazeboJoint::HebirosGazeboJoint | ( | const std::string & | name, |
| const std::string & | model_name, | ||
| bool | is_x8, | ||
| std::shared_ptr< ros::NodeHandle > | n | ||
| ) |
Definition at line 3 of file hebiros_gazebo_joint.cpp.
| bool HebirosGazeboJoint::isX8 | ( | ) | const |
Definition at line 22 of file hebiros_gazebo_joint.cpp.
| void HebirosGazeboJoint::SubIMU | ( | const boost::shared_ptr< sensor_msgs::Imu const > | data | ) |
Definition at line 17 of file hebiros_gazebo_joint.cpp.
| geometry_msgs::Vector3 HebirosGazeboJoint::accelerometer |
Definition at line 16 of file hebiros_gazebo_joint.h.
| int HebirosGazeboJoint::command_index |
Definition at line 20 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::effort_elapsed_error {} |
Definition at line 33 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::effort_prev_error {} |
Definition at line 32 of file hebiros_gazebo_joint.h.
| int HebirosGazeboJoint::feedback_index |
Definition at line 19 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::gear_ratio {} |
Definition at line 27 of file hebiros_gazebo_joint.h.
| geometry_msgs::Vector3 HebirosGazeboJoint::gyro |
Definition at line 17 of file hebiros_gazebo_joint.h.
| ros::Subscriber HebirosGazeboJoint::imu_subscriber |
Definition at line 35 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::low_pass_alpha {} |
Definition at line 26 of file hebiros_gazebo_joint.h.
| std::string HebirosGazeboJoint::model_name |
Definition at line 15 of file hebiros_gazebo_joint.h.
| std::string HebirosGazeboJoint::name |
Definition at line 14 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::position_elapsed_error {} |
Definition at line 29 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::position_prev_error {} |
Definition at line 28 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::prev_force {} |
Definition at line 25 of file hebiros_gazebo_joint.h.
| hebiros::sim::TemperatureModel HebirosGazeboJoint::temperature |
Definition at line 22 of file hebiros_gazebo_joint.h.
| hebiros::sim::TemperatureSafetyController HebirosGazeboJoint::temperature_safety {155} |
Definition at line 23 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::velocity_elapsed_error {} |
Definition at line 31 of file hebiros_gazebo_joint.h.
| double HebirosGazeboJoint::velocity_prev_error {} |
Definition at line 30 of file hebiros_gazebo_joint.h.