gazebo_ros_imu_sensor.h
Go to the documentation of this file.
1 /* Copyright [2015] [Alessandro Settimi]
2  *
3  * email: ale.settimi@gmail.com
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.*/
16 
17 #ifndef GAZEBO_ROS_IMU_SENSOR_H
18 #define GAZEBO_ROS_IMU_SENSOR_H
19 
20 #include <gazebo/common/Plugin.hh>
21 #include <gazebo/common/UpdateInfo.hh>
22 #include <ignition/math/Vector3.hh>
23 #include <ignition/math/Pose3.hh>
24 #include <ros/ros.h>
25 #include <sensor_msgs/Imu.h>
26 #include <string>
27 
28 namespace gazebo
29 {
30  namespace sensors
31  {
32  class ImuSensor;
33  }
42  class GazeboRosImuSensor : public SensorPlugin
43  {
44  public:
48  virtual ~GazeboRosImuSensor();
52  virtual void Load(sensors::SensorPtr sensor_, sdf::ElementPtr sdf_);
53 
54  protected:
56  virtual void UpdateChild(const gazebo::common::UpdateInfo &/*_info*/);
57 
58  private:
60  bool LoadParameters();
64  double GuassianKernel(double mu, double sigma);
65 
71  sensor_msgs::Imu imu_msg;
72 
74  common::Time last_time;
76  gazebo::event::ConnectionPtr connection;
78  sensors::ImuSensor* sensor;
80  sdf::ElementPtr sdf;
82  ignition::math::Quaterniond orientation;
84  ignition::math::Vector3d accelerometer_data;
86  ignition::math::Vector3d gyroscope_data;
87 
88  //loaded parameters
90  std::string robot_namespace;
92  std::string topic_name;
94  std::string body_name;
96  double update_rate;
100  ignition::math::Pose3d offset;
101  };
102 }
103 
104 #endif //GAZEBO_ROS_IMU_SENSOR_H
gazebo::GazeboRosImuSensor::LoadParameters
bool LoadParameters()
Load the parameters from the sdf file.
Definition: gazebo_ros_imu_sensor.cpp:170
gazebo::GazeboRosImuSensor::last_time
common::Time last_time
last time on which the data was published.
Definition: gazebo_ros_imu_sensor.h:74
ros::Publisher
gazebo::GazeboRosImuSensor::imu_msg
sensor_msgs::Imu imu_msg
Ros IMU message.
Definition: gazebo_ros_imu_sensor.h:71
gazebo::GazeboRosImuSensor
Gazebo Ros imu sensor plugin.
Definition: gazebo_ros_imu_sensor.h:42
gazebo
gazebo::GazeboRosImuSensor::Load
virtual void Load(sensors::SensorPtr sensor_, sdf::ElementPtr sdf_)
Load the sensor.
Definition: gazebo_ros_imu_sensor.cpp:36
ros.h
gazebo::GazeboRosImuSensor::~GazeboRosImuSensor
virtual ~GazeboRosImuSensor()
Destructor.
Definition: gazebo_ros_imu_sensor.cpp:264
gazebo::GazeboRosImuSensor::orientation
ignition::math::Quaterniond orientation
Orientation data from the sensor.
Definition: gazebo_ros_imu_sensor.h:82
gazebo::GazeboRosImuSensor::body_name
std::string body_name
Name of the link of the IMU.
Definition: gazebo_ros_imu_sensor.h:94
gazebo::GazeboRosImuSensor::connection
gazebo::event::ConnectionPtr connection
Pointer to the update event connection.
Definition: gazebo_ros_imu_sensor.h:76
gazebo::GazeboRosImuSensor::offset
ignition::math::Pose3d offset
Offset parameter, position part is unused.
Definition: gazebo_ros_imu_sensor.h:100
gazebo::GazeboRosImuSensor::topic_name
std::string topic_name
The data is published on the topic named: /robot_namespace/topic_name.
Definition: gazebo_ros_imu_sensor.h:92
gazebo::GazeboRosImuSensor::sdf
sdf::ElementPtr sdf
Pointer to the sdf config file.
Definition: gazebo_ros_imu_sensor.h:80
gazebo::GazeboRosImuSensor::update_rate
double update_rate
Sensor update rate.
Definition: gazebo_ros_imu_sensor.h:96
gazebo::GazeboRosImuSensor::imu_data_publisher
ros::Publisher imu_data_publisher
Ros Publisher for imu data.
Definition: gazebo_ros_imu_sensor.h:69
gazebo::GazeboRosImuSensor::GazeboRosImuSensor
GazeboRosImuSensor()
Constructor.
Definition: gazebo_ros_imu_sensor.cpp:28
gazebo::GazeboRosImuSensor::accelerometer_data
ignition::math::Vector3d accelerometer_data
Linear acceleration data from the sensor.
Definition: gazebo_ros_imu_sensor.h:84
gazebo::GazeboRosImuSensor::gyroscope_data
ignition::math::Vector3d gyroscope_data
Angular velocity data from the sensor.
Definition: gazebo_ros_imu_sensor.h:86
gazebo::GazeboRosImuSensor::sensor
sensors::ImuSensor * sensor
Pointer to the sensor.
Definition: gazebo_ros_imu_sensor.h:78
gazebo::GazeboRosImuSensor::robot_namespace
std::string robot_namespace
The data is published on the topic named: /robot_namespace/topic_name.
Definition: gazebo_ros_imu_sensor.h:90
gazebo::GazeboRosImuSensor::node
ros::NodeHandle * node
Ros NodeHandle pointer.
Definition: gazebo_ros_imu_sensor.h:67
gazebo::GazeboRosImuSensor::GuassianKernel
double GuassianKernel(double mu, double sigma)
Gaussian noise generator.
Definition: gazebo_ros_imu_sensor.cpp:156
gazebo::GazeboRosImuSensor::gaussian_noise
double gaussian_noise
Gaussian noise.
Definition: gazebo_ros_imu_sensor.h:98
gazebo::GazeboRosImuSensor::UpdateChild
virtual void UpdateChild(const gazebo::common::UpdateInfo &)
Update the sensor.
Definition: gazebo_ros_imu_sensor.cpp:92
ros::NodeHandle


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55