hebiros_gazebo_joint.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "ros/ros.h"
4 #include "sensor_msgs/Imu.h"
5 #include "geometry_msgs/Vector3.h"
8 
9 class HebirosGazeboJoint : public std::enable_shared_from_this<HebirosGazeboJoint> {
10 
11 public:
12 
13  // TODO: Make these private.
14  std::string name;
15  std::string model_name;
16  geometry_msgs::Vector3 accelerometer;
17  geometry_msgs::Vector3 gyro;
18 
21 
24 
25  double prev_force {};
26  double low_pass_alpha {};
27  double gear_ratio {};
32  double effort_prev_error {};
34 
36 
37  HebirosGazeboJoint(const std::string& name, const std::string& model_name, bool is_x8, std::shared_ptr<ros::NodeHandle> n);
38 
40  bool isX8() const;
41 
42 };
hebiros::sim::TemperatureModel temperature
void SubIMU(const boost::shared_ptr< sensor_msgs::Imu const > data)
geometry_msgs::Vector3 accelerometer
ros::Subscriber imu_subscriber
HebirosGazeboJoint(const std::string &name, const std::string &model_name, bool is_x8, std::shared_ptr< ros::NodeHandle > n)
geometry_msgs::Vector3 gyro
hebiros::sim::TemperatureSafetyController temperature_safety


hebiros_gazebo_plugin
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:13:55