Public Member Functions | Protected Attributes
rotors_hil::HilInterface Class Reference

#include <hil_interface.h>

Inheritance diagram for rotors_hil::HilInterface:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual std::vector
< mavros_msgs::Mavlink > 
CollectData ()=0
 Gather data collected from ROS messages into MAVLINK messages.
virtual
EIGEN_MAKE_ALIGNED_OPERATOR_NEW 
~HilInterface ()
 Destructor.

Protected Attributes

ros::Subscriber air_speed_sub_
 ROS air speed subscriber.
ros::Subscriber gps_sub_
 ROS GPS subscriber.
ros::Subscriber ground_speed_sub_
 ROS ground speed subscriber.
HilData hil_data_
 Object for storing the latest data.
HilListeners hil_listeners_
 Object with callbacks for receiving data.
ros::Subscriber imu_sub_
 ROS IMU subscriber.
ros::Subscriber mag_sub_
 ROS magnetometer subscriber.
boost::mutex mtx_
 Mutex lock for thread safety of reading hil data.
ros::NodeHandle nh_
 ROS node handle.
ros::Subscriber pressure_sub_
 ROS air pressure subscriber.
Eigen::Quaterniond q_S_B_
 Rotation, in quaternion form, from body into sensor (NED) frame.
Eigen::Matrix3f R_S_B_
 Rotation, in matrix form, from body into sensor (NED) frame.

Detailed Description

Definition at line 48 of file hil_interface.h.


Constructor & Destructor Documentation

virtual EIGEN_MAKE_ALIGNED_OPERATOR_NEW rotors_hil::HilInterface::~HilInterface ( ) [inline, virtual]

Destructor.

Definition at line 53 of file hil_interface.h.


Member Function Documentation

virtual std::vector<mavros_msgs::Mavlink> rotors_hil::HilInterface::CollectData ( ) [pure virtual]

Gather data collected from ROS messages into MAVLINK messages.

Returns:
Vector of MAVLINK messages (in MAVROS format) to be publised.

Implemented in rotors_hil::HilStateLevelInterface, and rotors_hil::HilSensorLevelInterface.


Member Data Documentation

ROS air speed subscriber.

Definition at line 64 of file hil_interface.h.

ROS GPS subscriber.

Definition at line 67 of file hil_interface.h.

ROS ground speed subscriber.

Definition at line 70 of file hil_interface.h.

Object for storing the latest data.

Definition at line 88 of file hil_interface.h.

Object with callbacks for receiving data.

Definition at line 91 of file hil_interface.h.

ROS IMU subscriber.

Definition at line 73 of file hil_interface.h.

ROS magnetometer subscriber.

Definition at line 76 of file hil_interface.h.

Mutex lock for thread safety of reading hil data.

Definition at line 94 of file hil_interface.h.

ROS node handle.

Definition at line 61 of file hil_interface.h.

ROS air pressure subscriber.

Definition at line 79 of file hil_interface.h.

Eigen::Quaterniond rotors_hil::HilInterface::q_S_B_ [protected]

Rotation, in quaternion form, from body into sensor (NED) frame.

Definition at line 82 of file hil_interface.h.

Eigen::Matrix3f rotors_hil::HilInterface::R_S_B_ [protected]

Rotation, in matrix form, from body into sensor (NED) frame.

Definition at line 85 of file hil_interface.h.


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


rotors_hil_interface
Author(s): Pavel Vechersky
autogenerated on Thu Apr 18 2019 02:43:51