Public Member Functions | Private Types | Private Member Functions | Private Attributes
mav::FlyerInterface Class Reference

#include <flyer_interface.h>

List of all members.

Public Member Functions

 FlyerInterface (ros::NodeHandle nh, ros::NodeHandle nh_private)
virtual ~FlyerInterface ()

Private Types

typedef
dynamic_reconfigure::Server
< CommConfig
CfgCommServer
typedef
dynamic_reconfigure::Server
< CtrlConfig
CfgCtrlServer
typedef
dynamic_reconfigure::Server
< PIDVXConfig
CfgVXServer
typedef
dynamic_reconfigure::Server
< PIDVYConfig
CfgVYServer
typedef
dynamic_reconfigure::Server
< PIDVZConfig
CfgVZServer
typedef
dynamic_reconfigure::Server
< PIDXConfig
CfgXServer
typedef
dynamic_reconfigure::Server
< PIDYawConfig
CfgYawServer
typedef
dynamic_reconfigure::Server
< PIDYConfig
CfgYServer
typedef
dynamic_reconfigure::Server
< PIDZConfig
CfgZServer
typedef flyer_interface::CommConfig CommConfig
typedef flyer_interface::CtrlConfig CtrlConfig
typedef
flyer_interface::PIDVXConfig 
PIDVXConfig
typedef
flyer_interface::PIDVYConfig 
PIDVYConfig
typedef
flyer_interface::PIDVZConfig 
PIDVZConfig
typedef flyer_interface::PIDXConfig PIDXConfig
typedef
flyer_interface::PIDYawConfig 
PIDYawConfig
typedef flyer_interface::PIDYConfig PIDYConfig
typedef flyer_interface::PIDZConfig PIDZConfig
typedef geometry_msgs::PoseStamped PoseStamped
typedef
message_filters::Subscriber
< PoseStamped
PoseStampedSubscriber
typedef
message_filters::Synchronizer
< SyncPolicy
Synchronizer
typedef
message_filters::sync_policies::ApproximateTime
< PoseStamped, TwistStamped
SyncPolicy
typedef geometry_msgs::TwistStamped TwistStamped
typedef
message_filters::Subscriber
< TwistStamped
TwistStampedSubscriber

Private Member Functions

bool advanceState (mav_srvs::AdvanceState::Request &req, mav_srvs::AdvanceState::Response &res)
void cmdPitchCallback (const mav_msgs::Pitch::ConstPtr pitch_msg)
void cmdPoseCallback (const geometry_msgs::PoseStamped::ConstPtr cmd_pose_msg)
void cmdRollCallback (const mav_msgs::Roll::ConstPtr roll_msg)
void cmdThrustCallback (const mav_msgs::Thrust::ConstPtr thrust_msg)
void cmdTimerCallback (const ros::TimerEvent &event)
void cmdVelCallback (const geometry_msgs::TwistStamped::ConstPtr cmd_vel_msg)
void cmdYawRateCallback (const mav_msgs::YawRate::ConstPtr yaw_rate_msg)
bool estop (mav_srvs::ESTOP::Request &req, mav_srvs::ESTOP::Response &res)
bool getFlightState (mav_srvs::GetFlightState::Request &req, mav_srvs::GetFlightState::Response &res)
void heightCallback (const mav_msgs::Height::ConstPtr height_msg)
void initializeParams ()
bool land (mav_srvs::Land::Request &req, mav_srvs::Land::Response &res)
void laserCallback (const PoseStamped::ConstPtr pose_msg, const TwistStamped::ConstPtr twist_msg)
void processCtrlDebugData (uint8_t *buf, uint32_t bufLength)
void processFlightStateData (uint8_t *buf, uint32_t bufLength)
void processImuData (uint8_t *buf, uint32_t bufLength)
void processPoseData (uint8_t *buf, uint32_t bufLength)
void processRCData (uint8_t *buf, uint32_t bufLength)
void processStatusData (uint8_t *buf, uint32_t bufLength)
void processTimeSyncData (uint8_t *buf, uint32_t bufLength)
void reconfig_comm_callback (CommConfig &config, uint32_t level)
void reconfig_ctrl_callback (CtrlConfig &config, uint32_t level)
void reconfig_vx_callback (PIDVXConfig &config, uint32_t level)
void reconfig_vy_callback (PIDVYConfig &config, uint32_t level)
void reconfig_vz_callback (PIDVZConfig &config, uint32_t level)
void reconfig_x_callback (PIDXConfig &config, uint32_t level)
void reconfig_y_callback (PIDYConfig &config, uint32_t level)
void reconfig_yaw_callback (PIDYawConfig &config, uint32_t level)
void reconfig_z_callback (PIDZConfig &config, uint32_t level)
bool retreatState (mav_srvs::AdvanceState::Request &req, mav_srvs::AdvanceState::Response &res)
void sendCommConfig ()
void sendCtrlConfig ()
void sendKFConfig (bool reset)
void sendPIDConfig ()
bool setCtrlType (mav_srvs::SetCtrlType::Request &req, mav_srvs::SetCtrlType::Response &res)
bool takeoff (mav_srvs::Takeoff::Request &req, mav_srvs::Takeoff::Response &res)
bool toggleEngage (mav_srvs::ToggleEngage::Request &req, mav_srvs::ToggleEngage::Response &res)

Private Attributes

ros::ServiceServer advance_state_srv_
std::string base_frame_
ros::Publisher battery_voltage_publisher_
int baudrate_
CfgCommServer cfg_comm_srv_
CfgCtrlServer cfg_ctrl_srv_
CfgVXServer cfg_vx_srv_
CfgVYServer cfg_vy_srv_
CfgVZServer cfg_vz_srv_
CfgXServer cfg_x_srv_
CfgYServer cfg_y_srv_
CfgYawServer cfg_yaw_srv_
CfgZServer cfg_z_srv_
float cmd_pitch_
ros::Subscriber cmd_pitch_subscriber_
ros::Subscriber cmd_pose_subscriber_
float cmd_roll_
ros::Subscriber cmd_roll_subscriber_
float cmd_thrust_
ros::Subscriber cmd_thrust_subscriber_
ros::Timer cmd_timer_
ros::Subscriber cmd_vel_subscriber_
float cmd_yaw_rate_
ros::Subscriber cmd_yaw_rate_subscriber_
SerialCommunication comm_
bool connected_
ros::Publisher cpu_load_avg_publisher_
int cpu_load_index_
ros::Publisher cpu_load_publisher_
std::vector< double > cpu_loads_
MAV_CTRL_CFG_PKT ctrl_cfg_packet_
ros::Publisher debug_ax_bf_publisher_
ros::Publisher debug_ay_bf_publisher_
ros::Publisher debug_az_publisher_
ros::Publisher debug_cmd_pitch_publisher_
ros::Publisher debug_cmd_roll_publisher_
ros::Publisher debug_cmd_thrust_publisher_
ros::Publisher debug_cmd_yaw_publisher_
ros::Publisher debug_cmd_yaw_rate_publisher_
ros::Publisher debug_err_vx_bf_publisher_
ros::Publisher debug_err_vy_bf_publisher_
ros::Publisher debug_err_x_bf_publisher_
ros::Publisher debug_err_y_bf_publisher_
ros::Publisher debug_imu_wf_publisher_
ros::Publisher debug_pid_x_i_term_publisher_
ros::Publisher debug_pid_y_i_term_publisher_
ros::Publisher debug_pid_yaw_i_term_publisher_
ros::Publisher debug_pid_z_i_term_publisher_
ros::Publisher debug_pitch_publisher_
ros::Publisher debug_roll_publisher_
ros::Publisher debug_vx_bf_publisher_
ros::Publisher debug_vy_bf_publisher_
ros::Publisher debug_yaw_publisher_
bool enable_kf_x_
bool enable_kf_y_
bool enable_kf_yaw_
bool enable_kf_z_
ros::ServiceServer estop_srv_
std::string fixed_frame_
uint8_t flight_state_
ros::Publisher flight_state_publisher_
ros::ServiceServer get_flight_state_srv_
ros::Subscriber height_subscriber_
ros::Publisher imu_publisher_
ros::ServiceServer land_srv_
boost::shared_ptr
< PoseStampedSubscriber
laser_pose_subscriber_
boost::shared_ptr
< TwistStampedSubscriber
laser_vel_subscriber_
ros::NodeHandle nh_
ros::NodeHandle nh_private_
MAV_PID_CFG_PKT pid_cfg_packet_
ros::Publisher pose_publisher_
bool publish_debug_
bool publish_pose_
double q_x_
double q_y_
double q_yaw_
double q_z_
double r_vx_
double r_vy_
double r_vz_
double r_vz_p_
double r_x_
double r_y_
double r_yaw_
double r_z_
ros::ServiceServer retreat_state_srv_
std::string serial_port_rx_
std::string serial_port_tx_
ros::ServiceServer set_ctrl_type_srv_
boost::mutex state_mutex_
boost::shared_ptr< Synchronizersync_
ros::ServiceServer takeoff_srv_
tf::TransformBroadcaster tf_broadcaster_
tf::TransformListener tf_listener_
ros::ServiceServer toggle_engage_srv_
MAV_TX_FREQ_CFG_PKT tx_freq_cfg_packet_
ros::Publisher vel_publisher_

Detailed Description

Definition at line 80 of file flyer_interface.h.


Member Typedef Documentation

typedef dynamic_reconfigure::Server<CommConfig> mav::FlyerInterface::CfgCommServer [private]

Definition at line 99 of file flyer_interface.h.

typedef dynamic_reconfigure::Server<CtrlConfig> mav::FlyerInterface::CfgCtrlServer [private]

Definition at line 100 of file flyer_interface.h.

typedef dynamic_reconfigure::Server<PIDVXConfig> mav::FlyerInterface::CfgVXServer [private]

Definition at line 95 of file flyer_interface.h.

typedef dynamic_reconfigure::Server<PIDVYConfig> mav::FlyerInterface::CfgVYServer [private]

Definition at line 96 of file flyer_interface.h.

typedef dynamic_reconfigure::Server<PIDVZConfig> mav::FlyerInterface::CfgVZServer [private]

Definition at line 97 of file flyer_interface.h.

typedef dynamic_reconfigure::Server<PIDXConfig> mav::FlyerInterface::CfgXServer [private]

Definition at line 92 of file flyer_interface.h.

typedef dynamic_reconfigure::Server<PIDYawConfig> mav::FlyerInterface::CfgYawServer [private]

Definition at line 98 of file flyer_interface.h.

typedef dynamic_reconfigure::Server<PIDYConfig> mav::FlyerInterface::CfgYServer [private]

Definition at line 93 of file flyer_interface.h.

typedef dynamic_reconfigure::Server<PIDZConfig> mav::FlyerInterface::CfgZServer [private]

Definition at line 94 of file flyer_interface.h.

typedef flyer_interface::CommConfig mav::FlyerInterface::CommConfig [private]

Definition at line 89 of file flyer_interface.h.

typedef flyer_interface::CtrlConfig mav::FlyerInterface::CtrlConfig [private]

Definition at line 90 of file flyer_interface.h.

typedef flyer_interface::PIDVXConfig mav::FlyerInterface::PIDVXConfig [private]

Definition at line 85 of file flyer_interface.h.

typedef flyer_interface::PIDVYConfig mav::FlyerInterface::PIDVYConfig [private]

Definition at line 86 of file flyer_interface.h.

typedef flyer_interface::PIDVZConfig mav::FlyerInterface::PIDVZConfig [private]

Definition at line 87 of file flyer_interface.h.

typedef flyer_interface::PIDXConfig mav::FlyerInterface::PIDXConfig [private]

Definition at line 82 of file flyer_interface.h.

typedef flyer_interface::PIDYawConfig mav::FlyerInterface::PIDYawConfig [private]

Definition at line 88 of file flyer_interface.h.

typedef flyer_interface::PIDYConfig mav::FlyerInterface::PIDYConfig [private]

Definition at line 83 of file flyer_interface.h.

typedef flyer_interface::PIDZConfig mav::FlyerInterface::PIDZConfig [private]

Definition at line 84 of file flyer_interface.h.

typedef geometry_msgs::PoseStamped mav::FlyerInterface::PoseStamped [private]

Definition at line 102 of file flyer_interface.h.

Definition at line 107 of file flyer_interface.h.

Definition at line 106 of file flyer_interface.h.

Definition at line 105 of file flyer_interface.h.

typedef geometry_msgs::TwistStamped mav::FlyerInterface::TwistStamped [private]

Definition at line 103 of file flyer_interface.h.

Definition at line 108 of file flyer_interface.h.


Constructor & Destructor Documentation

Definition at line 27 of file flyer_interface.cpp.

Definition at line 252 of file flyer_interface.cpp.


Member Function Documentation

Definition at line 763 of file flyer_interface.cpp.

Definition at line 905 of file flyer_interface.cpp.

void mav::FlyerInterface::cmdPoseCallback ( const geometry_msgs::PoseStamped::ConstPtr  cmd_pose_msg) [private]

Definition at line 353 of file flyer_interface.cpp.

Definition at line 900 of file flyer_interface.cpp.

Definition at line 915 of file flyer_interface.cpp.

void mav::FlyerInterface::cmdTimerCallback ( const ros::TimerEvent event) [private]

Definition at line 430 of file flyer_interface.cpp.

void mav::FlyerInterface::cmdVelCallback ( const geometry_msgs::TwistStamped::ConstPtr  cmd_vel_msg) [private]

Definition at line 406 of file flyer_interface.cpp.

Definition at line 910 of file flyer_interface.cpp.

Definition at line 785 of file flyer_interface.cpp.

Definition at line 796 of file flyer_interface.cpp.

Definition at line 419 of file flyer_interface.cpp.

Definition at line 257 of file flyer_interface.cpp.

Definition at line 853 of file flyer_interface.cpp.

void mav::FlyerInterface::laserCallback ( const PoseStamped::ConstPtr  pose_msg,
const TwistStamped::ConstPtr  twist_msg 
) [private]

Definition at line 334 of file flyer_interface.cpp.

void mav::FlyerInterface::processCtrlDebugData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 495 of file flyer_interface.cpp.

void mav::FlyerInterface::processFlightStateData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 748 of file flyer_interface.cpp.

void mav::FlyerInterface::processImuData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 711 of file flyer_interface.cpp.

void mav::FlyerInterface::processPoseData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 636 of file flyer_interface.cpp.

void mav::FlyerInterface::processRCData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 706 of file flyer_interface.cpp.

void mav::FlyerInterface::processStatusData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 603 of file flyer_interface.cpp.

void mav::FlyerInterface::processTimeSyncData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 875 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_comm_callback ( CommConfig config,
uint32_t  level 
) [private]

Definition at line 1024 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_ctrl_callback ( CtrlConfig config,
uint32_t  level 
) [private]

Definition at line 1009 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_vx_callback ( PIDVXConfig config,
uint32_t  level 
) [private]

Definition at line 960 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_vy_callback ( PIDVYConfig config,
uint32_t  level 
) [private]

Definition at line 972 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_vz_callback ( PIDVZConfig config,
uint32_t  level 
) [private]

Definition at line 984 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_x_callback ( PIDXConfig config,
uint32_t  level 
) [private]

Definition at line 920 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_y_callback ( PIDYConfig config,
uint32_t  level 
) [private]

Definition at line 934 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_yaw_callback ( PIDYawConfig config,
uint32_t  level 
) [private]

Definition at line 997 of file flyer_interface.cpp.

void mav::FlyerInterface::reconfig_z_callback ( PIDZConfig config,
uint32_t  level 
) [private]

Definition at line 948 of file flyer_interface.cpp.

Definition at line 774 of file flyer_interface.cpp.

Definition at line 483 of file flyer_interface.cpp.

Definition at line 489 of file flyer_interface.cpp.

void mav::FlyerInterface::sendKFConfig ( bool  reset) [private]

Definition at line 443 of file flyer_interface.cpp.

Definition at line 477 of file flyer_interface.cpp.

Definition at line 805 of file flyer_interface.cpp.

Definition at line 864 of file flyer_interface.cpp.

Definition at line 842 of file flyer_interface.cpp.


Member Data Documentation

Definition at line 185 of file flyer_interface.h.

std::string mav::FlyerInterface::base_frame_ [private]

Definition at line 226 of file flyer_interface.h.

Definition at line 154 of file flyer_interface.h.

Definition at line 221 of file flyer_interface.h.

Definition at line 131 of file flyer_interface.h.

Definition at line 123 of file flyer_interface.h.

Definition at line 127 of file flyer_interface.h.

Definition at line 128 of file flyer_interface.h.

Definition at line 129 of file flyer_interface.h.

Definition at line 124 of file flyer_interface.h.

Definition at line 125 of file flyer_interface.h.

Definition at line 130 of file flyer_interface.h.

Definition at line 126 of file flyer_interface.h.

Definition at line 208 of file flyer_interface.h.

Definition at line 143 of file flyer_interface.h.

Definition at line 146 of file flyer_interface.h.

Definition at line 208 of file flyer_interface.h.

Definition at line 142 of file flyer_interface.h.

Definition at line 208 of file flyer_interface.h.

Definition at line 145 of file flyer_interface.h.

Definition at line 194 of file flyer_interface.h.

Definition at line 147 of file flyer_interface.h.

Definition at line 208 of file flyer_interface.h.

Definition at line 144 of file flyer_interface.h.

Definition at line 206 of file flyer_interface.h.

Definition at line 200 of file flyer_interface.h.

Definition at line 156 of file flyer_interface.h.

Definition at line 204 of file flyer_interface.h.

Definition at line 155 of file flyer_interface.h.

std::vector<double> mav::FlyerInterface::cpu_loads_ [private]

Definition at line 203 of file flyer_interface.h.

Definition at line 212 of file flyer_interface.h.

Definition at line 176 of file flyer_interface.h.

Definition at line 177 of file flyer_interface.h.

Definition at line 178 of file flyer_interface.h.

Definition at line 161 of file flyer_interface.h.

Definition at line 160 of file flyer_interface.h.

Definition at line 163 of file flyer_interface.h.

Definition at line 164 of file flyer_interface.h.

Definition at line 162 of file flyer_interface.h.

Definition at line 174 of file flyer_interface.h.

Definition at line 175 of file flyer_interface.h.

Definition at line 172 of file flyer_interface.h.

Definition at line 173 of file flyer_interface.h.

Definition at line 159 of file flyer_interface.h.

Definition at line 165 of file flyer_interface.h.

Definition at line 166 of file flyer_interface.h.

Definition at line 167 of file flyer_interface.h.

Definition at line 168 of file flyer_interface.h.

Definition at line 170 of file flyer_interface.h.

Definition at line 169 of file flyer_interface.h.

Definition at line 179 of file flyer_interface.h.

Definition at line 180 of file flyer_interface.h.

Definition at line 171 of file flyer_interface.h.

Definition at line 228 of file flyer_interface.h.

Definition at line 229 of file flyer_interface.h.

Definition at line 231 of file flyer_interface.h.

Definition at line 230 of file flyer_interface.h.

Definition at line 192 of file flyer_interface.h.

std::string mav::FlyerInterface::fixed_frame_ [private]

Definition at line 225 of file flyer_interface.h.

Definition at line 201 of file flyer_interface.h.

Definition at line 153 of file flyer_interface.h.

Definition at line 191 of file flyer_interface.h.

Definition at line 139 of file flyer_interface.h.

Definition at line 152 of file flyer_interface.h.

Definition at line 189 of file flyer_interface.h.

Definition at line 135 of file flyer_interface.h.

Definition at line 136 of file flyer_interface.h.

Definition at line 119 of file flyer_interface.h.

Definition at line 120 of file flyer_interface.h.

Definition at line 211 of file flyer_interface.h.

Definition at line 150 of file flyer_interface.h.

Definition at line 216 of file flyer_interface.h.

Definition at line 218 of file flyer_interface.h.

double mav::FlyerInterface::q_x_ [private]

Definition at line 233 of file flyer_interface.h.

double mav::FlyerInterface::q_y_ [private]

Definition at line 233 of file flyer_interface.h.

double mav::FlyerInterface::q_yaw_ [private]

Definition at line 233 of file flyer_interface.h.

double mav::FlyerInterface::q_z_ [private]

Definition at line 233 of file flyer_interface.h.

double mav::FlyerInterface::r_vx_ [private]

Definition at line 235 of file flyer_interface.h.

double mav::FlyerInterface::r_vy_ [private]

Definition at line 235 of file flyer_interface.h.

double mav::FlyerInterface::r_vz_ [private]

Definition at line 235 of file flyer_interface.h.

double mav::FlyerInterface::r_vz_p_ [private]

Definition at line 235 of file flyer_interface.h.

double mav::FlyerInterface::r_x_ [private]

Definition at line 234 of file flyer_interface.h.

double mav::FlyerInterface::r_y_ [private]

Definition at line 234 of file flyer_interface.h.

double mav::FlyerInterface::r_yaw_ [private]

Definition at line 234 of file flyer_interface.h.

double mav::FlyerInterface::r_z_ [private]

Definition at line 234 of file flyer_interface.h.

Definition at line 186 of file flyer_interface.h.

std::string mav::FlyerInterface::serial_port_rx_ [private]

Definition at line 223 of file flyer_interface.h.

std::string mav::FlyerInterface::serial_port_tx_ [private]

Definition at line 222 of file flyer_interface.h.

Definition at line 190 of file flyer_interface.h.

boost::mutex mav::FlyerInterface::state_mutex_ [private]

Definition at line 198 of file flyer_interface.h.

boost::shared_ptr<Synchronizer> mav::FlyerInterface::sync_ [private]

Definition at line 134 of file flyer_interface.h.

Definition at line 188 of file flyer_interface.h.

Definition at line 183 of file flyer_interface.h.

Definition at line 182 of file flyer_interface.h.

Definition at line 187 of file flyer_interface.h.

Definition at line 210 of file flyer_interface.h.

Definition at line 151 of file flyer_interface.h.


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


flyer_interface
Author(s): Ivan Dryanovski
autogenerated on Thu Jan 2 2014 11:28:38