Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
rosflight_io::rosflightIO Class Reference

#include <rosflight_io.h>

Inheritance diagram for rosflight_io::rosflightIO:
Inheritance graph
[legend]

Public Member Functions

virtual void handle_mavlink_message (const mavlink_message_t &msg)
 The handler function for mavlink messages to be implemented by derived classes. More...
 
virtual void on_new_param_received (std::string name, double value)
 Called when a parameter is received from the autopilot for the first time. More...
 
virtual void on_param_value_updated (std::string name, double value)
 Called when an updated value is received for a parameter. More...
 
virtual void on_params_saved_change (bool unsaved_changes)
 Called when the status of whether there are unsaved parameters changes. More...
 
 rosflightIO ()
 
 ~rosflightIO ()
 

Static Public Attributes

static constexpr float HEARTBEAT_PERIOD = 1
 
static constexpr float PARAMETER_PERIOD = 3
 
static constexpr float VERSION_PERIOD = 10
 

Private Member Functions

void auxCommandCallback (rosflight_msgs::AuxCommand::ConstPtr msg)
 
bool calibrateAirspeedSrvCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
bool calibrateBaroSrvCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
bool calibrateImuBiasSrvCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
bool calibrateRCTrimSrvCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
void check_error_code (uint8_t current, uint8_t previous, ROSFLIGHT_ERROR_CODE code, std::string name)
 
void commandCallback (rosflight_msgs::Command::ConstPtr msg)
 
void externalAttitudeCallback (geometry_msgs::Quaternion::ConstPtr msg)
 
ros::Time fcu_time_to_ros_time (std::chrono::nanoseconds fcu_time)
 
std::string get_major_minor_version (const std::string &version)
 
void handle_attitude_quaternion_msg (const mavlink_message_t &msg)
 
void handle_battery_status_msg (const mavlink_message_t &msg)
 
void handle_command_ack_msg (const mavlink_message_t &msg)
 
void handle_diff_pressure_msg (const mavlink_message_t &msg)
 
void handle_hard_error_msg (const mavlink_message_t &msg)
 
void handle_heartbeat_msg (const mavlink_message_t &msg)
 
void handle_named_command_struct_msg (const mavlink_message_t &msg)
 
void handle_named_value_float_msg (const mavlink_message_t &msg)
 
void handle_named_value_int_msg (const mavlink_message_t &msg)
 
void handle_rc_channels_raw_msg (const mavlink_message_t &msg)
 
void handle_rosflight_gnss_full_msg (const mavlink_message_t &msg)
 
void handle_rosflight_gnss_msg (const mavlink_message_t &msg)
 
void handle_rosflight_output_raw_msg (const mavlink_message_t &msg)
 
void handle_small_baro_msg (const mavlink_message_t &msg)
 
void handle_small_imu_msg (const mavlink_message_t &msg)
 
void handle_small_mag_msg (const mavlink_message_t &msg)
 
void handle_small_range_msg (const mavlink_message_t &msg)
 
void handle_status_msg (const mavlink_message_t &msg)
 
void handle_statustext_msg (const mavlink_message_t &msg)
 
void handle_version_msg (const mavlink_message_t &msg)
 
void heartbeatTimerCallback (const ros::TimerEvent &e)
 
bool paramGetSrvCallback (rosflight_msgs::ParamGet::Request &req, rosflight_msgs::ParamGet::Response &res)
 
bool paramLoadFromFileCallback (rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
 
bool paramSaveToFileCallback (rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
 
bool paramSetSrvCallback (rosflight_msgs::ParamSet::Request &req, rosflight_msgs::ParamSet::Response &res)
 
void paramTimerCallback (const ros::TimerEvent &e)
 
bool paramWriteSrvCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
bool rebootSrvCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
bool rebootToBootloaderSrvCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
 
void request_version ()
 
template<class T >
saturate (T value, T min, T max)
 
void send_heartbeat ()
 
void versionTimerCallback (const ros::TimerEvent &e)
 

Private Attributes

ros::Publisher attitude_pub_
 
geometry_msgs::Quaternion attitude_quat_
 
ros::Subscriber aux_command_sub_
 
ros::Publisher baro_pub_
 
ros::Publisher battery_status_pub_
 
ros::ServiceServer calibrate_airspeed_srv_
 
ros::ServiceServer calibrate_baro_srv_
 
ros::ServiceServer calibrate_rc_srv_
 
ros::Subscriber command_sub_
 
ros::Publisher diff_pressure_pub_
 
ros::Publisher error_pub_
 
ros::Publisher euler_pub_
 
ros::Subscriber extatt_sub_
 
std::string frame_id_
 
ros::Publisher gnss_full_pub_
 
ros::Publisher gnss_pub_
 
ros::Timer heartbeat_timer_
 
ros::ServiceServer imu_calibrate_bias_srv_
 
ros::ServiceServer imu_calibrate_temp_srv_
 
ros::Publisher imu_pub_
 
ros::Publisher imu_temp_pub_
 
ros::Publisher lidar_pub_
 
rosflight::ROSLogger logger_
 
ros::Publisher mag_pub_
 
mavrosflight::MavlinkCommmavlink_comm_
 
mavrosflight::MavROSflight< rosflight::ROSLogger > * mavrosflight_
 
std::map< std::string, ros::Publishernamed_command_struct_pubs_
 
std::map< std::string, ros::Publishernamed_value_float_pubs_
 
std::map< std::string, ros::Publishernamed_value_int_pubs_
 
ros::Publisher nav_sat_fix_pub_
 
ros::NodeHandle nh_
 
ros::Publisher output_raw_pub_
 
ros::ServiceServer param_get_srv_
 
ros::ServiceServer param_load_from_file_srv_
 
ros::ServiceServer param_save_to_file_srv_
 
ros::ServiceServer param_set_srv_
 
ros::Timer param_timer_
 
ros::ServiceServer param_write_srv_
 
mavlink_rosflight_status_t prev_status_
 
ros::Publisher rc_raw_pub_
 
ros::ServiceServer reboot_bootloader_srv_
 
ros::ServiceServer reboot_srv_
 
ros::Publisher sonar_pub_
 
ros::Publisher status_pub_
 
ros::Publisher temperature_pub_
 
rosflight::ROSTimeInterface time_interface_
 
ros::Publisher time_reference_pub_
 
rosflight::ROSTimerProvider timer_provider_
 
ros::Publisher twist_stamped_pub_
 
ros::Publisher unsaved_params_pub_
 
ros::Publisher version_pub_
 
ros::Timer version_timer_
 

Detailed Description

Definition at line 91 of file rosflight_io.h.

Constructor & Destructor Documentation

rosflight_io::rosflightIO::rosflightIO ( )
Todo:
move this into the MavROSflight constructor

Definition at line 57 of file rosflight_io.cpp.

rosflight_io::rosflightIO::~rosflightIO ( )

Definition at line 148 of file rosflight_io.cpp.

Member Function Documentation

void rosflight_io::rosflightIO::auxCommandCallback ( rosflight_msgs::AuxCommand::ConstPtr  msg)
private

Definition at line 951 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::calibrateAirspeedSrvCallback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Definition at line 1077 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::calibrateBaroSrvCallback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Definition at line 1086 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::calibrateImuBiasSrvCallback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Definition at line 1009 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::calibrateRCTrimSrvCallback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Definition at line 1019 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::check_error_code ( uint8_t  current,
uint8_t  previous,
ROSFLIGHT_ERROR_CODE  code,
std::string  name 
)
private

Definition at line 1066 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::commandCallback ( rosflight_msgs::Command::ConstPtr  msg)
private
Todo:
these are hard-coded to match right now; may want to replace with something more robust

Definition at line 919 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::externalAttitudeCallback ( geometry_msgs::Quaternion::ConstPtr  msg)
private

Definition at line 965 of file rosflight_io.cpp.

ros::Time rosflight_io::rosflightIO::fcu_time_to_ros_time ( std::chrono::nanoseconds  fcu_time)
private

Definition at line 705 of file rosflight_io.cpp.

std::string rosflight_io::rosflightIO::get_major_minor_version ( const std::string &  version)
private

Definition at line 712 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_attitude_quaternion_msg ( const mavlink_message_t &  msg)
private

Definition at line 405 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_battery_status_msg ( const mavlink_message_t &  msg)
private

Definition at line 778 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_command_ack_msg ( const mavlink_message_t &  msg)
private

Definition at line 359 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_diff_pressure_msg ( const mavlink_message_t &  msg)
private

Definition at line 519 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_hard_error_msg ( const mavlink_message_t &  msg)
private

Definition at line 759 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_heartbeat_msg ( const mavlink_message_t &  msg)
private

Definition at line 254 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_mavlink_message ( const mavlink_message_t &  msg)
virtual

The handler function for mavlink messages to be implemented by derived classes.

Parameters
msgThe mavlink message to handle

Implements mavrosflight::MavlinkListenerInterface.

Definition at line 154 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_named_command_struct_msg ( const mavlink_message_t &  msg)
private

Definition at line 589 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_named_value_float_msg ( const mavlink_message_t &  msg)
private

Definition at line 566 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_named_value_int_msg ( const mavlink_message_t &  msg)
private

Definition at line 543 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_rc_channels_raw_msg ( const mavlink_message_t &  msg)
private

Definition at line 495 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_rosflight_gnss_full_msg ( const mavlink_message_t &  msg)
private

Definition at line 880 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_rosflight_gnss_msg ( const mavlink_message_t &  msg)
private

Definition at line 794 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_rosflight_output_raw_msg ( const mavlink_message_t &  msg)
private

Definition at line 476 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_small_baro_msg ( const mavlink_message_t &  msg)
private

Definition at line 622 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_small_imu_msg ( const mavlink_message_t &  msg)
private

Definition at line 442 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_small_mag_msg ( const mavlink_message_t &  msg)
private
Todo:
calibration, correct units, floating point message type

Definition at line 646 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_small_range_msg ( const mavlink_message_t &  msg)
private

Definition at line 667 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_status_msg ( const mavlink_message_t &  msg)
private

Definition at line 259 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_statustext_msg ( const mavlink_message_t &  msg)
private

Definition at line 374 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::handle_version_msg ( const mavlink_message_t &  msg)
private

Definition at line 722 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::heartbeatTimerCallback ( const ros::TimerEvent e)
private

Definition at line 1048 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::on_new_param_received ( std::string  name,
double  value 
)
virtual

Called when a parameter is received from the autopilot for the first time.

Parameters
nameThe name of the parameter
valueThe value of the parameter

Implements mavrosflight::ParamListenerInterface.

Definition at line 228 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::on_param_value_updated ( std::string  name,
double  value 
)
virtual

Called when an updated value is received for a parameter.

Parameters
nameThe name of the parameter
valueThe updated value of the parameter

Implements mavrosflight::ParamListenerInterface.

Definition at line 233 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::on_params_saved_change ( bool  unsaved_changes)
virtual

Called when the status of whether there are unsaved parameters changes.

Parameters
unsaved_changesTrue if there are parameters that have been set but not saved on the autopilot

Implements mavrosflight::ParamListenerInterface.

Definition at line 238 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::paramGetSrvCallback ( rosflight_msgs::ParamGet::Request &  req,
rosflight_msgs::ParamGet::Response &  res 
)
private

Definition at line 972 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::paramLoadFromFileCallback ( rosflight_msgs::ParamFile::Request &  req,
rosflight_msgs::ParamFile::Response &  res 
)
private

Definition at line 1002 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::paramSaveToFileCallback ( rosflight_msgs::ParamFile::Request &  req,
rosflight_msgs::ParamFile::Response &  res 
)
private

Definition at line 995 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::paramSetSrvCallback ( rosflight_msgs::ParamSet::Request &  req,
rosflight_msgs::ParamSet::Response &  res 
)
private

Definition at line 978 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::paramTimerCallback ( const ros::TimerEvent e)
private

Definition at line 1028 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::paramWriteSrvCallback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Definition at line 984 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::rebootSrvCallback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Definition at line 1095 of file rosflight_io.cpp.

bool rosflight_io::rosflightIO::rebootToBootloaderSrvCallback ( std_srvs::Trigger::Request &  req,
std_srvs::Trigger::Response &  res 
)
private

Definition at line 1104 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::request_version ( )
private

Definition at line 1053 of file rosflight_io.cpp.

template<class T >
T rosflight_io::rosflightIO::saturate ( value,
min,
max 
)
inlineprivate

Definition at line 161 of file rosflight_io.h.

void rosflight_io::rosflightIO::send_heartbeat ( )
private

Definition at line 1059 of file rosflight_io.cpp.

void rosflight_io::rosflightIO::versionTimerCallback ( const ros::TimerEvent e)
private

Definition at line 1043 of file rosflight_io.cpp.

Member Data Documentation

ros::Publisher rosflight_io::rosflightIO::attitude_pub_
private

Definition at line 187 of file rosflight_io.h.

geometry_msgs::Quaternion rosflight_io::rosflightIO::attitude_quat_
private

Definition at line 215 of file rosflight_io.h.

ros::Subscriber rosflight_io::rosflightIO::aux_command_sub_
private

Definition at line 169 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::baro_pub_
private

Definition at line 179 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::battery_status_pub_
private

Definition at line 193 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::calibrate_airspeed_srv_
private

Definition at line 207 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::calibrate_baro_srv_
private

Definition at line 206 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::calibrate_rc_srv_
private

Definition at line 205 of file rosflight_io.h.

ros::Subscriber rosflight_io::rosflightIO::command_sub_
private

Definition at line 168 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::diff_pressure_pub_
private

Definition at line 177 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::error_pub_
private

Definition at line 192 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::euler_pub_
private

Definition at line 188 of file rosflight_io.h.

ros::Subscriber rosflight_io::rosflightIO::extatt_sub_
private

Definition at line 170 of file rosflight_io.h.

std::string rosflight_io::rosflightIO::frame_id_
private

Definition at line 218 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::gnss_full_pub_
private

Definition at line 182 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::gnss_pub_
private

Definition at line 181 of file rosflight_io.h.

constexpr float rosflight_io::rosflightIO::HEARTBEAT_PERIOD = 1
static

Definition at line 103 of file rosflight_io.h.

ros::Timer rosflight_io::rosflightIO::heartbeat_timer_
private

Definition at line 213 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::imu_calibrate_bias_srv_
private

Definition at line 203 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::imu_calibrate_temp_srv_
private

Definition at line 204 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::imu_pub_
private

Definition at line 173 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::imu_temp_pub_
private

Definition at line 174 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::lidar_pub_
private

Definition at line 191 of file rosflight_io.h.

rosflight::ROSLogger rosflight_io::rosflightIO::logger_
private

Definition at line 223 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::mag_pub_
private

Definition at line 186 of file rosflight_io.h.

mavrosflight::MavlinkComm* rosflight_io::rosflightIO::mavlink_comm_
private

Definition at line 220 of file rosflight_io.h.

mavrosflight::MavROSflight<rosflight::ROSLogger>* rosflight_io::rosflightIO::mavrosflight_
private

Definition at line 221 of file rosflight_io.h.

std::map<std::string, ros::Publisher> rosflight_io::rosflightIO::named_command_struct_pubs_
private

Definition at line 196 of file rosflight_io.h.

std::map<std::string, ros::Publisher> rosflight_io::rosflightIO::named_value_float_pubs_
private

Definition at line 195 of file rosflight_io.h.

std::map<std::string, ros::Publisher> rosflight_io::rosflightIO::named_value_int_pubs_
private

Definition at line 194 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::nav_sat_fix_pub_
private

Definition at line 183 of file rosflight_io.h.

ros::NodeHandle rosflight_io::rosflightIO::nh_
private

Definition at line 166 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::output_raw_pub_
private

Definition at line 175 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::param_get_srv_
private

Definition at line 198 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::param_load_from_file_srv_
private

Definition at line 202 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::param_save_to_file_srv_
private

Definition at line 201 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::param_set_srv_
private

Definition at line 199 of file rosflight_io.h.

ros::Timer rosflight_io::rosflightIO::param_timer_
private

Definition at line 211 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::param_write_srv_
private

Definition at line 200 of file rosflight_io.h.

constexpr float rosflight_io::rosflightIO::PARAMETER_PERIOD = 3
static

Definition at line 105 of file rosflight_io.h.

mavlink_rosflight_status_t rosflight_io::rosflightIO::prev_status_
private

Definition at line 216 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::rc_raw_pub_
private

Definition at line 176 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::reboot_bootloader_srv_
private

Definition at line 209 of file rosflight_io.h.

ros::ServiceServer rosflight_io::rosflightIO::reboot_srv_
private

Definition at line 208 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::sonar_pub_
private

Definition at line 180 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::status_pub_
private

Definition at line 189 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::temperature_pub_
private

Definition at line 178 of file rosflight_io.h.

rosflight::ROSTimeInterface rosflight_io::rosflightIO::time_interface_
private

Definition at line 224 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::time_reference_pub_
private

Definition at line 185 of file rosflight_io.h.

rosflight::ROSTimerProvider rosflight_io::rosflightIO::timer_provider_
private

Definition at line 225 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::twist_stamped_pub_
private

Definition at line 184 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::unsaved_params_pub_
private

Definition at line 172 of file rosflight_io.h.

constexpr float rosflight_io::rosflightIO::VERSION_PERIOD = 10
static

Definition at line 104 of file rosflight_io.h.

ros::Publisher rosflight_io::rosflightIO::version_pub_
private

Definition at line 190 of file rosflight_io.h.

ros::Timer rosflight_io::rosflightIO::version_timer_
private

Definition at line 212 of file rosflight_io.h.


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


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:09:29