hebiros_gazebo_joint.cpp
Go to the documentation of this file.
1 #include <hebiros_gazebo_joint.h>
2 
3 HebirosGazeboJoint::HebirosGazeboJoint(const std::string& name_,
4  const std::string& model_name_,
5  bool is_x8, // TODO: do this better...
6  std::shared_ptr<ros::NodeHandle> n)
7  : name(name_), model_name(model_name_),
8  temperature(is_x8 ?
9  hebiros::sim::TemperatureModel::createX8() :
10  hebiros::sim::TemperatureModel::createX5()) {
11  this->imu_subscriber = n->subscribe<sensor_msgs::Imu>(
12  "hebiros_gazebo_plugin/imu/"+name,
13  100, boost::bind(&HebirosGazeboJoint::SubIMU, this, _1));
14 }
15 
16 //Subscriber which receives IMU feedback from gazebo
18  this->accelerometer = data->linear_acceleration;
19  this->gyro = data->angular_velocity;
20 }
21 
23  return (model_name == "X8_3" ||
24  model_name == "X8_9" ||
25  model_name == "X8_16");
26 }
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_gazebo_plugin
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:13:55