32 #ifndef ROSFLIGHT_SIM_ROSFLIGHT_SIL_H 33 #define ROSFLIGHT_SIM_ROSFLIGHT_SIL_H 35 #include <geometry_msgs/Vector3.h> 36 #include <nav_msgs/Odometry.h> 38 #include <gazebo/common/Plugin.hh> 39 #include <gazebo/common/common.hh> 40 #include <gazebo/gazebo.hh> 41 #include <gazebo/physics/physics.hh> 44 #include <rosflight.h> 62 void Reset()
override;
63 void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf)
override;
64 void OnUpdate(
const gazebo::common::UpdateInfo& _info);
110 #endif // ROSFLIGHT_SIM_ROSFLIGHT_SIL_H
ros::Publisher truth_NWU_pub_
gazebo::math::Vector3 GazeboVector
rosflight_firmware::Mavlink comm_
Eigen::Matrix3d rotation_to_eigen_from_gazebo(GazeboQuaternion vec)
Eigen::Vector3d vec3_to_eigen_from_gazebo(GazeboVector vec)
Eigen::Matrix< double, 6, 1 > forces_
MAVForcesAndMoments * mav_dynamics_
gazebo::physics::EntityPtr parent_link_
GazeboVector vec3_to_gazebo_from_eigen(Eigen::Vector3d vec)
Eigen::Matrix< double, 6, 1 > applied_forces_
gazebo::math::Pose GazeboPose
gazebo::physics::JointPtr joint_
rosflight_firmware::ROSflight firmware_
gazebo::physics::WorldPtr world_
void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override
ros::Subscriber wind_sub_
void OnUpdate(const gazebo::common::UpdateInfo &_info)
gazebo::event::ConnectionPtr updateConnection_
ros::Publisher truth_NED_pub_
gazebo::physics::LinkPtr link_
void windCallback(const geometry_msgs::Vector3 &msg)
gazebo::physics::ModelPtr model_
gazebo::math::Quaternion GazeboQuaternion