rosflight_io.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch and James Jackson, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
37 #ifndef ROSFLIGHT_IO_MAVROSFLIGHT_ROS_H
38 #define ROSFLIGHT_IO_MAVROSFLIGHT_ROS_H
39 
40 #include <map>
41 #include <string>
42 
43 #include <ros/ros.h>
44 
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>
51 
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>
59 
60 #include <std_srvs/Trigger.h>
61 
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>
72 
73 
74 #include <rosflight_msgs/ParamFile.h>
75 #include <rosflight_msgs/ParamGet.h>
76 #include <rosflight_msgs/ParamSet.h>
77 
82 
83 #include <geometry_msgs/Quaternion.h>
84 
85 namespace rosflight_io
86 {
87 
88 class rosflightIO :
91 {
92 public:
93  rosflightIO();
94  ~rosflightIO();
95 
96  virtual void handle_mavlink_message(const mavlink_message_t &msg);
97 
98  virtual void on_new_param_received(std::string name, double value);
99  virtual void on_param_value_updated(std::string name, double value);
100  virtual void on_params_saved_change(bool unsaved_changes);
101 
102  static constexpr float HEARTBEAT_PERIOD = 1; //Time between heartbeat messages
103 
104 private:
105 
106  // handle mavlink messages
107  void handle_heartbeat_msg(const mavlink_message_t &msg);
108  void handle_status_msg(const mavlink_message_t &msg);
109  void handle_command_ack_msg(const mavlink_message_t &msg);
110  void handle_statustext_msg(const mavlink_message_t &msg);
111  void handle_attitude_quaternion_msg(const mavlink_message_t &msg);
112  void handle_small_imu_msg(const mavlink_message_t &msg);
113  void handle_rosflight_output_raw_msg(const mavlink_message_t &msg);
114  void handle_rc_channels_raw_msg(const mavlink_message_t &msg);
115  void handle_diff_pressure_msg(const mavlink_message_t &msg);
116  void handle_small_baro_msg(const mavlink_message_t &msg);
117  void handle_small_mag_msg(const mavlink_message_t &msg);
118  void handle_rosflight_gnss_msg(const mavlink_message_t &msg);
119  void handle_rosflight_gnss_raw_msg(const mavlink_message_t &msg);
120  void handle_named_value_int_msg(const mavlink_message_t &msg);
121  void handle_named_value_float_msg(const mavlink_message_t &msg);
122  void handle_named_command_struct_msg(const mavlink_message_t &msg);
123  void handle_small_range_msg(const mavlink_message_t &msg);
124  void handle_version_msg(const mavlink_message_t &msg);
125  void handle_hard_error_msg(const mavlink_message_t &msg);
126 
127  // ROS message callbacks
128  void commandCallback(rosflight_msgs::Command::ConstPtr msg);
129  void attitudeCorrectionCallback(geometry_msgs::Quaternion::ConstPtr msg);
130 
131  // ROS service callbacks
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);
134  bool paramWriteSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
135  bool paramSaveToFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res);
136  bool paramLoadFromFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res);
137  bool calibrateImuBiasSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
138  bool calibrateRCTrimSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
139  bool calibrateBaroSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
140  bool calibrateAirspeedSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
141  bool rebootSrvCallback(std_srvs::Trigger::Request & req, std_srvs::Trigger::Response &res);
142  bool rebootToBootloaderSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
143 
144  // timer callbacks
145  void paramTimerCallback(const ros::TimerEvent &e);
146  void versionTimerCallback(const ros::TimerEvent &e);
148 
149  // helpers
150  void request_version();
151  void send_heartbeat();
152  void check_error_code(uint8_t current, uint8_t previous, ROSFLIGHT_ERROR_CODE code, std::string name);
153 
154  template<class T> inline T saturate(T value, T min, T max)
155  {
156  return value < min ? min : (value > max ? max : value);
157  }
158 
159 
161 
164 
186  std::map<std::string, ros::Publisher> named_value_int_pubs_;
187  std::map<std::string, ros::Publisher> named_value_float_pubs_;
188  std::map<std::string, ros::Publisher> named_command_struct_pubs_;
189 
202 
206 
207  geometry_msgs::Quaternion attitude_quat_;
209 
210  std::string frame_id_;
211 
214 };
215 
216 } // namespace rosflight_io
217 
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_
Definition: rosflight_io.h:177
void handle_diff_pressure_msg(const mavlink_message_t &msg)
ros::Publisher attitude_pub_
Definition: rosflight_io.h:180
Describes an interface classes can implement to receive and handle mavlink messages.
ros::Publisher unsaved_params_pub_
Definition: rosflight_io.h:165
static constexpr float HEARTBEAT_PERIOD
Definition: rosflight_io.h:102
void handle_heartbeat_msg(const mavlink_message_t &msg)
ros::Publisher output_raw_pub_
Definition: rosflight_io.h:168
ros::ServiceServer calibrate_rc_srv_
Definition: rosflight_io.h:197
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)
ros::Publisher baro_pub_
Definition: rosflight_io.h:172
virtual void on_params_saved_change(bool unsaved_changes)
Called when the status of whether there are unsaved parameters changes.
ros::ServiceServer reboot_srv_
Definition: rosflight_io.h:200
bool paramLoadFromFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
ros::Publisher nav_sat_fix_pub_
Definition: rosflight_io.h:176
geometry_msgs::Quaternion attitude_quat_
Definition: rosflight_io.h:207
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_
Definition: rosflight_io.h:182
void handle_rosflight_output_raw_msg(const mavlink_message_t &msg)
mavrosflight::MavlinkComm * mavlink_comm_
Definition: rosflight_io.h:212
void handle_named_value_int_msg(const mavlink_message_t &msg)
ros::Publisher lidar_pub_
Definition: rosflight_io.h:184
ros::Publisher sonar_pub_
Definition: rosflight_io.h:173
ros::Publisher time_reference_pub_
Definition: rosflight_io.h:178
void handle_small_imu_msg(const mavlink_message_t &msg)
void handle_named_command_struct_msg(const mavlink_message_t &msg)
mavrosflight::MavROSflight * mavrosflight_
Definition: rosflight_io.h:213
ros::Publisher imu_temp_pub_
Definition: rosflight_io.h:167
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_
Definition: rosflight_io.h:191
ROSFLIGHT_ERROR_CODE
Definition: rosflight.h:113
mavlink_rosflight_status_t prev_status_
Definition: rosflight_io.h:208
ros::ServiceServer calibrate_baro_srv_
Definition: rosflight_io.h:198
void commandCallback(rosflight_msgs::Command::ConstPtr msg)
Describes an interface classes can implement to receive and handle mavlink messages.
ros::Publisher version_pub_
Definition: rosflight_io.h:183
ros::Publisher error_pub_
Definition: rosflight_io.h:185
ros::ServiceServer imu_calibrate_temp_srv_
Definition: rosflight_io.h:196
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_
Definition: rosflight_io.h:170
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_
Definition: rosflight_io.h:195
ros::Publisher gnss_pub_
Definition: rosflight_io.h:174
T saturate(T value, T min, T max)
Definition: rosflight_io.h:154
ros::ServiceServer param_save_to_file_srv_
Definition: rosflight_io.h:193
ros::Publisher euler_pub_
Definition: rosflight_io.h:181
ros::Subscriber command_sub_
Definition: rosflight_io.h:162
ros::ServiceServer calibrate_airspeed_srv_
Definition: rosflight_io.h:199
bool paramSaveToFileCallback(rosflight_msgs::ParamFile::Request &req, rosflight_msgs::ParamFile::Response &res)
std::map< std::string, ros::Publisher > named_value_int_pubs_
Definition: rosflight_io.h:186
ros::Publisher temperature_pub_
Definition: rosflight_io.h:171
void attitudeCorrectionCallback(geometry_msgs::Quaternion::ConstPtr msg)
void handle_rosflight_gnss_msg(const mavlink_message_t &msg)
ros::Publisher rc_raw_pub_
Definition: rosflight_io.h:169
bool rebootToBootloaderSrvCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer param_write_srv_
Definition: rosflight_io.h:192
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_
Definition: rosflight_io.h:201
ros::ServiceServer param_get_srv_
Definition: rosflight_io.h:190
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_
Definition: rosflight_io.h:188
ros::Publisher gnss_raw_pub_
Definition: rosflight_io.h:175
ros::Subscriber attitude_sub_
Definition: rosflight_io.h:163
std::map< std::string, ros::Publisher > named_value_float_pubs_
Definition: rosflight_io.h:187
ros::ServiceServer param_load_from_file_srv_
Definition: rosflight_io.h:194


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:13