37 #ifndef ROSFLIGHT_IO_MAVROSFLIGHT_ROS_H 38 #define ROSFLIGHT_IO_MAVROSFLIGHT_ROS_H 45 #include <std_msgs/Bool.h> 46 #include <std_msgs/Float32.h> 47 #include <std_msgs/Int32.h> 48 #include <std_msgs/String.h> 49 #include <geometry_msgs/Quaternion.h> 50 #include <geometry_msgs/TwistStamped.h> 52 #include <sensor_msgs/Imu.h> 53 #include <sensor_msgs/FluidPressure.h> 54 #include <sensor_msgs/MagneticField.h> 55 #include <sensor_msgs/Temperature.h> 56 #include <sensor_msgs/Range.h> 57 #include <sensor_msgs/NavSatFix.h> 58 #include <sensor_msgs/TimeReference.h> 60 #include <std_srvs/Trigger.h> 62 #include <rosflight_msgs/Attitude.h> 63 #include <rosflight_msgs/Barometer.h> 64 #include <rosflight_msgs/Airspeed.h> 65 #include <rosflight_msgs/Command.h> 66 #include <rosflight_msgs/OutputRaw.h> 67 #include <rosflight_msgs/RCRaw.h> 68 #include <rosflight_msgs/Status.h> 69 #include <rosflight_msgs/Error.h> 70 #include <rosflight_msgs/GNSSRaw.h> 71 #include <rosflight_msgs/GNSS.h> 74 #include <rosflight_msgs/ParamFile.h> 75 #include <rosflight_msgs/ParamGet.h> 76 #include <rosflight_msgs/ParamSet.h> 83 #include <geometry_msgs/Quaternion.h> 132 bool paramGetSrvCallback(rosflight_msgs::ParamGet::Request &req, rosflight_msgs::ParamGet::Response &res);
133 bool paramSetSrvCallback(rosflight_msgs::ParamSet::Request &req, rosflight_msgs::ParamSet::Response &res);
135 bool paramSaveToFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res);
141 bool rebootSrvCallback(std_srvs::Trigger::Request & req, std_srvs::Trigger::Response &res);
154 template<
class T>
inline T
saturate(T value, T min, T max)
156 return value < min ? min : (value > max ? max : value);
218 #endif // ROSFLIGHT_IO_MAVROSFLIGHT_ROS_H void versionTimerCallback(const ros::TimerEvent &e)
void handle_small_mag_msg(const mavlink_message_t &msg)
bool calibrateRCTrimSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::Publisher twist_stamped_pub_
void handle_diff_pressure_msg(const mavlink_message_t &msg)
ros::Publisher attitude_pub_
Describes an interface classes can implement to receive and handle mavlink messages.
ros::Publisher unsaved_params_pub_
static constexpr float HEARTBEAT_PERIOD
void handle_heartbeat_msg(const mavlink_message_t &msg)
ros::Publisher output_raw_pub_
ros::ServiceServer calibrate_rc_srv_
virtual void handle_mavlink_message(const mavlink_message_t &msg)
The handler function for mavlink messages to be implemented by derived classes.
void handle_small_baro_msg(const mavlink_message_t &msg)
void handle_command_ack_msg(const mavlink_message_t &msg)
virtual void on_param_value_updated(std::string name, double value)
Called when an updated value is received for a parameter.
void handle_small_range_msg(const mavlink_message_t &msg)
void check_error_code(uint8_t current, uint8_t previous, ROSFLIGHT_ERROR_CODE code, std::string name)
virtual void on_params_saved_change(bool unsaved_changes)
Called when the status of whether there are unsaved parameters changes.
ros::ServiceServer reboot_srv_
bool paramLoadFromFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
ros::Publisher nav_sat_fix_pub_
geometry_msgs::Quaternion attitude_quat_
void handle_attitude_quaternion_msg(const mavlink_message_t &msg)
void handle_statustext_msg(const mavlink_message_t &msg)
void paramTimerCallback(const ros::TimerEvent &e)
bool calibrateBaroSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void handle_status_msg(const mavlink_message_t &msg)
ros::Publisher status_pub_
ros::Timer version_timer_
void handle_rosflight_output_raw_msg(const mavlink_message_t &msg)
mavrosflight::MavlinkComm * mavlink_comm_
void handle_named_value_int_msg(const mavlink_message_t &msg)
ros::Publisher lidar_pub_
ros::Publisher sonar_pub_
ros::Publisher time_reference_pub_
void handle_small_imu_msg(const mavlink_message_t &msg)
void handle_named_command_struct_msg(const mavlink_message_t &msg)
mavrosflight::MavROSflight * mavrosflight_
ros::Publisher imu_temp_pub_
bool paramGetSrvCallback(rosflight_msgs::ParamGet::Request &req, rosflight_msgs::ParamGet::Response &res)
void heartbeatTimerCallback(const ros::TimerEvent &e)
bool rebootSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer param_set_srv_
ros::Timer heartbeat_timer_
mavlink_rosflight_status_t prev_status_
ros::ServiceServer calibrate_baro_srv_
void commandCallback(rosflight_msgs::Command::ConstPtr msg)
Describes an interface classes can implement to receive and handle mavlink messages.
ros::Publisher version_pub_
ros::Publisher error_pub_
ros::ServiceServer imu_calibrate_temp_srv_
void handle_named_value_float_msg(const mavlink_message_t &msg)
bool paramSetSrvCallback(rosflight_msgs::ParamSet::Request &req, rosflight_msgs::ParamSet::Response &res)
bool paramWriteSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::Publisher diff_pressure_pub_
bool calibrateImuBiasSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void handle_hard_error_msg(const mavlink_message_t &msg)
void handle_version_msg(const mavlink_message_t &msg)
void handle_rc_channels_raw_msg(const mavlink_message_t &msg)
ros::ServiceServer imu_calibrate_bias_srv_
T saturate(T value, T min, T max)
ros::ServiceServer param_save_to_file_srv_
ros::Publisher euler_pub_
ros::Subscriber command_sub_
ros::ServiceServer calibrate_airspeed_srv_
bool paramSaveToFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
std::map< std::string, ros::Publisher > named_value_int_pubs_
ros::Publisher temperature_pub_
void attitudeCorrectionCallback(geometry_msgs::Quaternion::ConstPtr msg)
void handle_rosflight_gnss_msg(const mavlink_message_t &msg)
ros::Publisher rc_raw_pub_
bool rebootToBootloaderSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer param_write_srv_
virtual void on_new_param_received(std::string name, double value)
Called when a parameter is received from the autopilot for the first time.
ros::ServiceServer reboot_bootloader_srv_
ros::ServiceServer param_get_srv_
bool calibrateAirspeedSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void handle_rosflight_gnss_raw_msg(const mavlink_message_t &msg)
std::map< std::string, ros::Publisher > named_command_struct_pubs_
ros::Publisher gnss_raw_pub_
ros::Subscriber attitude_sub_
std::map< std::string, ros::Publisher > named_value_float_pubs_
ros::ServiceServer param_load_from_file_srv_