Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboFwDynamicsPlugin Class Reference

#include <gazebo_fw_dynamics_plugin.h>

Inheritance diagram for gazebo::GazeboFwDynamicsPlugin:
Inheritance graph
[legend]

Public Member Functions

 GazeboFwDynamicsPlugin ()
 Constructor. More...
 
virtual ~GazeboFwDynamicsPlugin ()
 Destructor. More...
 

Protected Member Functions

void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 Called when the plugin is first created, and after the world has been loaded. This function should not be blocking. More...
 
double NormalizedInputToAngle (const ControlSurface &surface, double input)
 Convert control surface input that is normalized in range [-1, 1] to a physical deflection angle value. More...
 
void OnUpdate (const common::UpdateInfo &)
 This gets called by the world update start event. More...
 
void UpdateForcesAndMoments ()
 Calculates the forces and moments to be applied to the fixed-wing body. More...
 

Private Member Functions

void ActuatorsCallback (GzActuatorsMsgPtr &actuators_msg)
 Processes the actuator commands. More...
 
void CreatePubsAndSubs ()
 Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. More...
 
void RollPitchYawrateThrustCallback (GzRollPitchYawrateThrustMsgPtr &roll_pitch_yawrate_thrust_msg)
 Process the roll_pitch_yawrate_thrust commands. More...
 
void WindSpeedCallback (GzWindSpeedMsgPtr &wind_speed_msg)
 Processes the wind speed readings. More...
 

Private Attributes

gazebo::transport::SubscriberPtr actuators_sub_
 Subscriber for receiving actuator commands. More...
 
std::string actuators_sub_topic_
 Topic name for actuator commands. More...
 
FWAerodynamicParameters aero_params_
 The aerodynamic properties of the aircraft. More...
 
double delta_aileron_left_
 Left aileron deflection [rad]. More...
 
double delta_aileron_right_
 Right aileron deflection [rad]. More...
 
double delta_elevator_
 Elevator deflection [rad]. More...
 
double delta_flap_
 Flap deflection [rad]. More...
 
double delta_rudder_
 Rudder deflection [rad]. More...
 
bool is_input_joystick_
 Are the input commands coming from a joystick (as opposed to a remote control via HIL interface, for example)? More...
 
physics::LinkPtr link_
 Pointer to the link. More...
 
physics::ModelPtr model_
 Pointer to the model. More...
 
std::string namespace_
 Transport namespace. More...
 
transport::NodePtr node_handle_
 Handle for the Gazebo node. More...
 
bool pubs_and_subs_created_
 Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate(). More...
 
gazebo::transport::SubscriberPtr roll_pitch_yawrate_thrust_sub_
 Subscriber for receiving roll_pitch_yawrate_thrust commands. More...
 
std::string roll_pitch_yawrate_thrust_sub_topic_
 Topic name for roll_pitch_yawrate_thrust commands. More...
 
double throttle_
 Throttle input, in range from 0 to 1. More...
 
event::ConnectionPtr updateConnection_
 Pointer to the update event connection. More...
 
FWVehicleParameters vehicle_params_
 The physical properties of the aircraft. More...
 
ignition::math::Vector3d W_wind_speed_W_B_
 Most current wind speed reading [m/s]. More...
 
gazebo::transport::SubscriberPtr wind_speed_sub_
 Subscriber ror receiving wind speed readings. More...
 
std::string wind_speed_sub_topic_
 Topic name for wind speed readings. More...
 
physics::WorldPtr world_
 Pointer to the world. More...
 

Detailed Description

Definition at line 50 of file gazebo_fw_dynamics_plugin.h.

Constructor & Destructor Documentation

◆ GazeboFwDynamicsPlugin()

gazebo::GazeboFwDynamicsPlugin::GazeboFwDynamicsPlugin ( )

Constructor.

Definition at line 24 of file gazebo_fw_dynamics_plugin.cpp.

◆ ~GazeboFwDynamicsPlugin()

gazebo::GazeboFwDynamicsPlugin::~GazeboFwDynamicsPlugin ( )
virtual

Destructor.

Definition at line 37 of file gazebo_fw_dynamics_plugin.cpp.

Member Function Documentation

◆ ActuatorsCallback()

void gazebo::GazeboFwDynamicsPlugin::ActuatorsCallback ( GzActuatorsMsgPtr actuators_msg)
private

Processes the actuator commands.

Converts control surface actuator inputs into physical angles before storing them and throttle values for later use in calculation of forces and moments.

Definition at line 358 of file gazebo_fw_dynamics_plugin.cpp.

◆ CreatePubsAndSubs()

void gazebo::GazeboFwDynamicsPlugin::CreatePubsAndSubs ( )
private

Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required.

Call this once the first time OnUpdate() is called (can't be called from Load() because there is no guarantee GazeboRosInterfacePlugin has loaded and listening to ConnectGazeboToRosTopic and ConnectRosToGazeboTopic messages).

Definition at line 290 of file gazebo_fw_dynamics_plugin.cpp.

◆ Load()

void gazebo::GazeboFwDynamicsPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
protected

Called when the plugin is first created, and after the world has been loaded. This function should not be blocking.

Definition at line 40 of file gazebo_fw_dynamics_plugin.cpp.

◆ NormalizedInputToAngle()

double gazebo::GazeboFwDynamicsPlugin::NormalizedInputToAngle ( const ControlSurface surface,
double  input 
)
protected

Convert control surface input that is normalized in range [-1, 1] to a physical deflection angle value.

Definition at line 284 of file gazebo_fw_dynamics_plugin.cpp.

◆ OnUpdate()

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

This gets called by the world update start event.

Definition at line 123 of file gazebo_fw_dynamics_plugin.cpp.

◆ RollPitchYawrateThrustCallback()

void gazebo::GazeboFwDynamicsPlugin::RollPitchYawrateThrustCallback ( GzRollPitchYawrateThrustMsgPtr roll_pitch_yawrate_thrust_msg)
private

Process the roll_pitch_yawrate_thrust commands.

Converts the inputs into physical angles before storing them and thrust values for later use in calculation of forces and moments.

Definition at line 378 of file gazebo_fw_dynamics_plugin.cpp.

◆ UpdateForcesAndMoments()

void gazebo::GazeboFwDynamicsPlugin::UpdateForcesAndMoments ( )
protected

Calculates the forces and moments to be applied to the fixed-wing body.

Definition at line 136 of file gazebo_fw_dynamics_plugin.cpp.

◆ WindSpeedCallback()

void gazebo::GazeboFwDynamicsPlugin::WindSpeedCallback ( GzWindSpeedMsgPtr wind_speed_msg)
private

Processes the wind speed readings.

Stores the most current wind speed reading for later use in calculation of forces and moments.

Definition at line 396 of file gazebo_fw_dynamics_plugin.cpp.

Member Data Documentation

◆ actuators_sub_

gazebo::transport::SubscriberPtr gazebo::GazeboFwDynamicsPlugin::actuators_sub_
private

Subscriber for receiving actuator commands.

Definition at line 105 of file gazebo_fw_dynamics_plugin.h.

◆ actuators_sub_topic_

std::string gazebo::GazeboFwDynamicsPlugin::actuators_sub_topic_
private

Topic name for actuator commands.

Definition at line 95 of file gazebo_fw_dynamics_plugin.h.

◆ aero_params_

FWAerodynamicParameters gazebo::GazeboFwDynamicsPlugin::aero_params_
private

The aerodynamic properties of the aircraft.

Definition at line 124 of file gazebo_fw_dynamics_plugin.h.

◆ delta_aileron_left_

double gazebo::GazeboFwDynamicsPlugin::delta_aileron_left_
private

Left aileron deflection [rad].

Definition at line 130 of file gazebo_fw_dynamics_plugin.h.

◆ delta_aileron_right_

double gazebo::GazeboFwDynamicsPlugin::delta_aileron_right_
private

Right aileron deflection [rad].

Definition at line 132 of file gazebo_fw_dynamics_plugin.h.

◆ delta_elevator_

double gazebo::GazeboFwDynamicsPlugin::delta_elevator_
private

Elevator deflection [rad].

Definition at line 134 of file gazebo_fw_dynamics_plugin.h.

◆ delta_flap_

double gazebo::GazeboFwDynamicsPlugin::delta_flap_
private

Flap deflection [rad].

Definition at line 136 of file gazebo_fw_dynamics_plugin.h.

◆ delta_rudder_

double gazebo::GazeboFwDynamicsPlugin::delta_rudder_
private

Rudder deflection [rad].

Definition at line 138 of file gazebo_fw_dynamics_plugin.h.

◆ is_input_joystick_

bool gazebo::GazeboFwDynamicsPlugin::is_input_joystick_
private

Are the input commands coming from a joystick (as opposed to a remote control via HIL interface, for example)?

Definition at line 77 of file gazebo_fw_dynamics_plugin.h.

◆ link_

physics::LinkPtr gazebo::GazeboFwDynamicsPlugin::link_
private

Pointer to the link.

Definition at line 116 of file gazebo_fw_dynamics_plugin.h.

◆ model_

physics::ModelPtr gazebo::GazeboFwDynamicsPlugin::model_
private

Pointer to the model.

Definition at line 114 of file gazebo_fw_dynamics_plugin.h.

◆ namespace_

std::string gazebo::GazeboFwDynamicsPlugin::namespace_
private

Transport namespace.

Definition at line 93 of file gazebo_fw_dynamics_plugin.h.

◆ node_handle_

transport::NodePtr gazebo::GazeboFwDynamicsPlugin::node_handle_
private

Handle for the Gazebo node.

Definition at line 102 of file gazebo_fw_dynamics_plugin.h.

◆ pubs_and_subs_created_

bool gazebo::GazeboFwDynamicsPlugin::pubs_and_subs_created_
private

Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate().

Definition at line 82 of file gazebo_fw_dynamics_plugin.h.

◆ roll_pitch_yawrate_thrust_sub_

gazebo::transport::SubscriberPtr gazebo::GazeboFwDynamicsPlugin::roll_pitch_yawrate_thrust_sub_
private

Subscriber for receiving roll_pitch_yawrate_thrust commands.

Definition at line 107 of file gazebo_fw_dynamics_plugin.h.

◆ roll_pitch_yawrate_thrust_sub_topic_

std::string gazebo::GazeboFwDynamicsPlugin::roll_pitch_yawrate_thrust_sub_topic_
private

Topic name for roll_pitch_yawrate_thrust commands.

Definition at line 97 of file gazebo_fw_dynamics_plugin.h.

◆ throttle_

double gazebo::GazeboFwDynamicsPlugin::throttle_
private

Throttle input, in range from 0 to 1.

Definition at line 140 of file gazebo_fw_dynamics_plugin.h.

◆ updateConnection_

event::ConnectionPtr gazebo::GazeboFwDynamicsPlugin::updateConnection_
private

Pointer to the update event connection.

Definition at line 118 of file gazebo_fw_dynamics_plugin.h.

◆ vehicle_params_

FWVehicleParameters gazebo::GazeboFwDynamicsPlugin::vehicle_params_
private

The physical properties of the aircraft.

Definition at line 127 of file gazebo_fw_dynamics_plugin.h.

◆ W_wind_speed_W_B_

ignition::math::Vector3d gazebo::GazeboFwDynamicsPlugin::W_wind_speed_W_B_
private

Most current wind speed reading [m/s].

Definition at line 121 of file gazebo_fw_dynamics_plugin.h.

◆ wind_speed_sub_

gazebo::transport::SubscriberPtr gazebo::GazeboFwDynamicsPlugin::wind_speed_sub_
private

Subscriber ror receiving wind speed readings.

Definition at line 109 of file gazebo_fw_dynamics_plugin.h.

◆ wind_speed_sub_topic_

std::string gazebo::GazeboFwDynamicsPlugin::wind_speed_sub_topic_
private

Topic name for wind speed readings.

Definition at line 99 of file gazebo_fw_dynamics_plugin.h.

◆ world_

physics::WorldPtr gazebo::GazeboFwDynamicsPlugin::world_
private

Pointer to the world.

Definition at line 112 of file gazebo_fw_dynamics_plugin.h.


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


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:04