Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
rosflight_sim::ROSflightSIL Class Reference

#include <rosflight_sil.h>

Inheritance diagram for rosflight_sim::ROSflightSIL:
Inheritance graph
[legend]

Public Member Functions

 ROSflightSIL ()
 
 ~ROSflightSIL ()
 

Protected Member Functions

void Load (gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override
 
void OnUpdate (const gazebo::common::UpdateInfo &_info)
 
void Reset () override
 

Private Member Functions

void publishTruth ()
 
Eigen::Matrix3d rotation_to_eigen_from_gazebo (GazeboQuaternion vec)
 
Eigen::Vector3d vec3_to_eigen_from_gazebo (GazeboVector vec)
 
GazeboVector vec3_to_gazebo_from_eigen (Eigen::Vector3d vec)
 
void windCallback (const geometry_msgs::Vector3 &msg)
 

Private Attributes

Eigen::Matrix< double, 6, 1 > applied_forces_
 
SIL_Board board_
 
rosflight_firmware::Mavlink comm_
 
rosflight_firmware::ROSflight firmware_
 
Eigen::Matrix< double, 6, 1 > forces_
 
GazeboPose initial_pose_
 
gazebo::physics::JointPtr joint_
 
gazebo::physics::LinkPtr link_
 
std::string link_name_
 
MAVForcesAndMomentsmav_dynamics_
 
std::string mav_type_
 
gazebo::physics::ModelPtr model_
 
std::string namespace_
 
ros::NodeHandlenh_
 
gazebo::physics::EntityPtr parent_link_
 
uint64_t start_time_us_
 
ros::Publisher truth_NED_pub_
 
ros::Publisher truth_NWU_pub_
 
gazebo::event::ConnectionPtr updateConnection_
 
ros::Subscriber wind_sub_
 
gazebo::physics::WorldPtr world_
 

Detailed Description

Definition at line 56 of file rosflight_sil.h.

Constructor & Destructor Documentation

rosflight_sim::ROSflightSIL::ROSflightSIL ( )

Definition at line 47 of file rosflight_sil.cpp.

rosflight_sim::ROSflightSIL::~ROSflightSIL ( )

Definition at line 54 of file rosflight_sil.cpp.

Member Function Documentation

void rosflight_sim::ROSflightSIL::Load ( gazebo::physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
overrideprotected

Definition at line 63 of file rosflight_sil.cpp.

void rosflight_sim::ROSflightSIL::OnUpdate ( const gazebo::common::UpdateInfo &  _info)
protected

Definition at line 127 of file rosflight_sil.cpp.

void rosflight_sim::ROSflightSIL::publishTruth ( )
private

Definition at line 174 of file rosflight_sil.cpp.

void rosflight_sim::ROSflightSIL::Reset ( )
overrideprotected

Definition at line 159 of file rosflight_sil.cpp.

Eigen::Matrix3d rosflight_sim::ROSflightSIL::rotation_to_eigen_from_gazebo ( GazeboQuaternion  vec)
private

Definition at line 226 of file rosflight_sil.cpp.

Eigen::Vector3d rosflight_sim::ROSflightSIL::vec3_to_eigen_from_gazebo ( GazeboVector  vec)
private

Definition at line 213 of file rosflight_sil.cpp.

GazeboVector rosflight_sim::ROSflightSIL::vec3_to_gazebo_from_eigen ( Eigen::Vector3d  vec)
private

Definition at line 220 of file rosflight_sil.cpp.

void rosflight_sim::ROSflightSIL::windCallback ( const geometry_msgs::Vector3 msg)
private

Definition at line 167 of file rosflight_sil.cpp.

Member Data Documentation

Eigen::Matrix<double, 6, 1> rosflight_sim::ROSflightSIL::applied_forces_
private

Definition at line 93 of file rosflight_sil.h.

SIL_Board rosflight_sim::ROSflightSIL::board_
private

Definition at line 71 of file rosflight_sil.h.

rosflight_firmware::Mavlink rosflight_sim::ROSflightSIL::comm_
private

Definition at line 72 of file rosflight_sil.h.

rosflight_firmware::ROSflight rosflight_sim::ROSflightSIL::firmware_
private

Definition at line 73 of file rosflight_sil.h.

Eigen::Matrix<double, 6, 1> rosflight_sim::ROSflightSIL::forces_
private

Definition at line 93 of file rosflight_sil.h.

GazeboPose rosflight_sim::ROSflightSIL::initial_pose_
private

Definition at line 101 of file rosflight_sil.h.

gazebo::physics::JointPtr rosflight_sim::ROSflightSIL::joint_
private

Definition at line 82 of file rosflight_sil.h.

gazebo::physics::LinkPtr rosflight_sim::ROSflightSIL::link_
private

Definition at line 81 of file rosflight_sil.h.

std::string rosflight_sim::ROSflightSIL::link_name_
private

Definition at line 77 of file rosflight_sil.h.

MAVForcesAndMoments* rosflight_sim::ROSflightSIL::mav_dynamics_
private

Definition at line 90 of file rosflight_sil.h.

std::string rosflight_sim::ROSflightSIL::mav_type_
private

Definition at line 75 of file rosflight_sil.h.

gazebo::physics::ModelPtr rosflight_sim::ROSflightSIL::model_
private

Definition at line 80 of file rosflight_sil.h.

std::string rosflight_sim::ROSflightSIL::namespace_
private

Definition at line 76 of file rosflight_sil.h.

ros::NodeHandle* rosflight_sim::ROSflightSIL::nh_
private

Definition at line 98 of file rosflight_sil.h.

gazebo::physics::EntityPtr rosflight_sim::ROSflightSIL::parent_link_
private

Definition at line 83 of file rosflight_sil.h.

uint64_t rosflight_sim::ROSflightSIL::start_time_us_
private

Definition at line 96 of file rosflight_sil.h.

ros::Publisher rosflight_sim::ROSflightSIL::truth_NED_pub_
private

Definition at line 87 of file rosflight_sil.h.

ros::Publisher rosflight_sim::ROSflightSIL::truth_NWU_pub_
private

Definition at line 88 of file rosflight_sil.h.

gazebo::event::ConnectionPtr rosflight_sim::ROSflightSIL::updateConnection_
private

Definition at line 84 of file rosflight_sil.h.

ros::Subscriber rosflight_sim::ROSflightSIL::wind_sub_
private

Definition at line 86 of file rosflight_sil.h.

gazebo::physics::WorldPtr rosflight_sim::ROSflightSIL::world_
private

Definition at line 79 of file rosflight_sil.h.


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


rosflight_sim
Author(s): James Jackson, Gary Ellingson, Daniel Koch
autogenerated on Wed Jul 3 2019 20:00:29