diff --git a/.gitmodules b/.gitmodules index 64c3a65aaf..b93d8e4a92 100644 --- a/.gitmodules +++ b/.gitmodules @@ -3,4 +3,4 @@ url = https://github.com/google/googletest [submodule "mavsdk-proto"] path = proto - url = https://github.com/mavlink/MAVSDK-Proto.git + url = https://github.com/akkawimo/MAVSDK-Proto.git diff --git a/proto b/proto index 14901895bc..e94f2bfa05 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 14901895bc8aa97676c50ec1c00d89d70bdd3b68 +Subproject commit e94f2bfa054acee3a811c10d5e95c0b0b6caa02c diff --git a/src/mavsdk/core/system_impl.cpp b/src/mavsdk/core/system_impl.cpp index 496b739d58..42bb5a1fc1 100644 --- a/src/mavsdk/core/system_impl.cpp +++ b/src/mavsdk/core/system_impl.cpp @@ -850,7 +850,6 @@ SystemImpl::make_command_ardupilot_mode(FlightMode flight_mode, uint8_t componen case MAV_TYPE::MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE::MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE::MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE::MAV_TYPE_VTOL_RESERVED4: case MAV_TYPE::MAV_TYPE_VTOL_RESERVED5: { const auto new_mode = flight_mode_to_ardupilot_plane_mode(flight_mode); if (new_mode == ardupilot::PlaneMode::Unknown) { diff --git a/src/mavsdk/plugins/action/action.cpp b/src/mavsdk/plugins/action/action.cpp index ac6b9993ba..fe16d70964 100644 --- a/src/mavsdk/plugins/action/action.cpp +++ b/src/mavsdk/plugins/action/action.cpp @@ -9,263 +9,328 @@ namespace mavsdk { + + + + Action::Action(System& system) : PluginBase(), _impl{std::make_unique(system)} {} -Action::Action(std::shared_ptr system) : - PluginBase(), - _impl{std::make_unique(system)} -{} +Action::Action(std::shared_ptr system) : PluginBase(), _impl{std::make_unique(system)} {} + Action::~Action() {} + + void Action::arm_async(const ResultCallback callback) { _impl->arm_async(callback); } + + Action::Result Action::arm() const { return _impl->arm(); } + + void Action::disarm_async(const ResultCallback callback) { _impl->disarm_async(callback); } + + Action::Result Action::disarm() const { return _impl->disarm(); } + + void Action::takeoff_async(const ResultCallback callback) { _impl->takeoff_async(callback); } + + Action::Result Action::takeoff() const { return _impl->takeoff(); } + + void Action::land_async(const ResultCallback callback) { _impl->land_async(callback); } + + Action::Result Action::land() const { return _impl->land(); } + + void Action::reboot_async(const ResultCallback callback) { _impl->reboot_async(callback); } + + Action::Result Action::reboot() const { return _impl->reboot(); } + + void Action::shutdown_async(const ResultCallback callback) { _impl->shutdown_async(callback); } + + Action::Result Action::shutdown() const { return _impl->shutdown(); } + + void Action::terminate_async(const ResultCallback callback) { _impl->terminate_async(callback); } + + Action::Result Action::terminate() const { return _impl->terminate(); } + + void Action::kill_async(const ResultCallback callback) { _impl->kill_async(callback); } + + Action::Result Action::kill() const { return _impl->kill(); } + + void Action::return_to_launch_async(const ResultCallback callback) { _impl->return_to_launch_async(callback); } + + Action::Result Action::return_to_launch() const { return _impl->return_to_launch(); } -void Action::goto_location_async( - double latitude_deg, - double longitude_deg, - float absolute_altitude_m, - float yaw_deg, - const ResultCallback callback) + + +void Action::goto_location_async(double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg, const ResultCallback callback) { _impl->goto_location_async(latitude_deg, longitude_deg, absolute_altitude_m, yaw_deg, callback); } -Action::Result Action::goto_location( - double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg) const + + +Action::Result Action::goto_location(double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg) const { return _impl->goto_location(latitude_deg, longitude_deg, absolute_altitude_m, yaw_deg); } -void Action::do_orbit_async( - float radius_m, - float velocity_ms, - OrbitYawBehavior yaw_behavior, - double latitude_deg, - double longitude_deg, - double absolute_altitude_m, - const ResultCallback callback) + + +void Action::do_orbit_async(float radius_m, float velocity_ms, OrbitYawBehavior yaw_behavior, double latitude_deg, double longitude_deg, double absolute_altitude_m, const ResultCallback callback) { - _impl->do_orbit_async( - radius_m, - velocity_ms, - yaw_behavior, - latitude_deg, - longitude_deg, - absolute_altitude_m, - callback); + _impl->do_orbit_async(radius_m, velocity_ms, yaw_behavior, latitude_deg, longitude_deg, absolute_altitude_m, callback); } -Action::Result Action::do_orbit( - float radius_m, - float velocity_ms, - OrbitYawBehavior yaw_behavior, - double latitude_deg, - double longitude_deg, - double absolute_altitude_m) const + + +Action::Result Action::do_orbit(float radius_m, float velocity_ms, OrbitYawBehavior yaw_behavior, double latitude_deg, double longitude_deg, double absolute_altitude_m) const { - return _impl->do_orbit( - radius_m, velocity_ms, yaw_behavior, latitude_deg, longitude_deg, absolute_altitude_m); + return _impl->do_orbit(radius_m, velocity_ms, yaw_behavior, latitude_deg, longitude_deg, absolute_altitude_m); } + + void Action::hold_async(const ResultCallback callback) { _impl->hold_async(callback); } + + Action::Result Action::hold() const { return _impl->hold(); } + + void Action::set_actuator_async(int32_t index, float value, const ResultCallback callback) { _impl->set_actuator_async(index, value, callback); } + + Action::Result Action::set_actuator(int32_t index, float value) const { return _impl->set_actuator(index, value); } + + void Action::transition_to_fixedwing_async(const ResultCallback callback) { _impl->transition_to_fixedwing_async(callback); } + + Action::Result Action::transition_to_fixedwing() const { return _impl->transition_to_fixedwing(); } + + void Action::transition_to_multicopter_async(const ResultCallback callback) { _impl->transition_to_multicopter_async(callback); } + + Action::Result Action::transition_to_multicopter() const { return _impl->transition_to_multicopter(); } + + void Action::get_takeoff_altitude_async(const GetTakeoffAltitudeCallback callback) { _impl->get_takeoff_altitude_async(callback); } + + std::pair Action::get_takeoff_altitude() const { return _impl->get_takeoff_altitude(); } + + void Action::set_takeoff_altitude_async(float altitude, const ResultCallback callback) { _impl->set_takeoff_altitude_async(altitude, callback); } + + Action::Result Action::set_takeoff_altitude(float altitude) const { return _impl->set_takeoff_altitude(altitude); } + + void Action::get_maximum_speed_async(const GetMaximumSpeedCallback callback) { _impl->get_maximum_speed_async(callback); } + + std::pair Action::get_maximum_speed() const { return _impl->get_maximum_speed(); } + + void Action::set_maximum_speed_async(float speed, const ResultCallback callback) { _impl->set_maximum_speed_async(speed, callback); } + + Action::Result Action::set_maximum_speed(float speed) const { return _impl->set_maximum_speed(speed); } + + void Action::get_return_to_launch_altitude_async(const GetReturnToLaunchAltitudeCallback callback) { _impl->get_return_to_launch_altitude_async(callback); } + + std::pair Action::get_return_to_launch_altitude() const { return _impl->get_return_to_launch_altitude(); } -void Action::set_return_to_launch_altitude_async( - float relative_altitude_m, const ResultCallback callback) + + +void Action::set_return_to_launch_altitude_async(float relative_altitude_m, const ResultCallback callback) { _impl->set_return_to_launch_altitude_async(relative_altitude_m, callback); } + + Action::Result Action::set_return_to_launch_altitude(float relative_altitude_m) const { return _impl->set_return_to_launch_altitude(relative_altitude_m); } + + void Action::set_current_speed_async(float speed_m_s, const ResultCallback callback) { _impl->set_current_speed_async(speed_m_s, callback); } + + Action::Result Action::set_current_speed(float speed_m_s) const { return _impl->set_current_speed(speed_m_s); } + + + std::ostream& operator<<(std::ostream& str, Action::Result const& result) { switch (result) { @@ -302,6 +367,8 @@ std::ostream& operator<<(std::ostream& str, Action::Result const& result) } } + + std::ostream& operator<<(std::ostream& str, Action::OrbitYawBehavior const& orbit_yaw_behavior) { switch (orbit_yaw_behavior) { @@ -320,4 +387,5 @@ std::ostream& operator<<(std::ostream& str, Action::OrbitYawBehavior const& orbi } } + } // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/action/include/plugins/action/action.h b/src/mavsdk/plugins/action/include/plugins/action/action.h index 1a67023077..6939627b22 100644 --- a/src/mavsdk/plugins/action/include/plugins/action/action.h +++ b/src/mavsdk/plugins/action/include/plugins/action/action.h @@ -13,20 +13,22 @@ #include #include + #include "plugin_base.h" #include "handle.h" namespace mavsdk { -class System; -class ActionImpl; + +class System;class ActionImpl; /** * @brief Enable simple actions such as arming, taking off, and landing. */ class Action : public PluginBase { public: + /** * @brief Constructor. Creates the plugin for a specific System. * @@ -53,11 +55,13 @@ class Action : public PluginBase { */ explicit Action(std::shared_ptr system); // new + /** * @brief Destructor (internal use only). */ ~Action() override; + /** * @brief Yaw behaviour during orbit flight. */ @@ -65,8 +69,7 @@ class Action : public PluginBase { HoldFrontToCircleCenter, /**< @brief Vehicle front points to the center (default). */ HoldInitialHeading, /**< @brief Vehicle front holds heading when message received. */ Uncontrolled, /**< @brief Yaw uncontrolled. */ - HoldFrontTangentToCircle, /**< @brief Vehicle front follows flight path (tangential to - circle). */ + HoldFrontTangentToCircle, /**< @brief Vehicle front follows flight path (tangential to circle). */ RcControlled, /**< @brief Yaw controlled by RC input. */ }; @@ -75,8 +78,11 @@ class Action : public PluginBase { * * @return A reference to the stream. */ - friend std::ostream& - operator<<(std::ostream& str, Action::OrbitYawBehavior const& orbit_yaw_behavior); + friend std::ostream& operator<<(std::ostream& str, Action::OrbitYawBehavior const& orbit_yaw_behavior); + + + + /** * @brief Possible results returned for action requests. @@ -88,8 +94,7 @@ class Action : public PluginBase { ConnectionError, /**< @brief Connection error. */ Busy, /**< @brief Vehicle is busy. */ CommandDenied, /**< @brief Command refused by vehicle. */ - CommandDeniedLandedStateUnknown, /**< @brief Command refused because landed state is - unknown. */ + CommandDeniedLandedStateUnknown, /**< @brief Command refused because landed state is unknown. */ CommandDeniedNotLanded, /**< @brief Command refused because vehicle not landed. */ Timeout, /**< @brief Request timed out. */ VtolTransitionSupportUnknown, /**< @brief Hybrid/VTOL transition support is unknown. */ @@ -106,11 +111,16 @@ class Action : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Action::Result const& result); + + /** * @brief Callback type for asynchronous Action calls. */ using ResultCallback = std::function; + + + /** * @brief Send command to arm the drone. * @@ -121,6 +131,8 @@ class Action : public PluginBase { */ void arm_async(const ResultCallback callback); + + /** * @brief Send command to arm the drone. * @@ -133,6 +145,9 @@ class Action : public PluginBase { */ Result arm() const; + + + /** * @brief Send command to disarm the drone. * @@ -143,6 +158,8 @@ class Action : public PluginBase { */ void disarm_async(const ResultCallback callback); + + /** * @brief Send command to disarm the drone. * @@ -155,6 +172,9 @@ class Action : public PluginBase { */ Result disarm() const; + + + /** * @brief Send command to take off and hover. * @@ -167,6 +187,8 @@ class Action : public PluginBase { */ void takeoff_async(const ResultCallback callback); + + /** * @brief Send command to take off and hover. * @@ -181,6 +203,9 @@ class Action : public PluginBase { */ Result takeoff() const; + + + /** * @brief Send command to land at the current position. * @@ -190,6 +215,8 @@ class Action : public PluginBase { */ void land_async(const ResultCallback callback); + + /** * @brief Send command to land at the current position. * @@ -201,6 +228,9 @@ class Action : public PluginBase { */ Result land() const; + + + /** * @brief Send command to reboot the drone components. * @@ -210,6 +240,8 @@ class Action : public PluginBase { */ void reboot_async(const ResultCallback callback); + + /** * @brief Send command to reboot the drone components. * @@ -221,6 +253,9 @@ class Action : public PluginBase { */ Result reboot() const; + + + /** * @brief Send command to shut down the drone components. * @@ -232,6 +267,8 @@ class Action : public PluginBase { */ void shutdown_async(const ResultCallback callback); + + /** * @brief Send command to shut down the drone components. * @@ -245,21 +282,24 @@ class Action : public PluginBase { */ Result shutdown() const; + + + /** * @brief Send command to terminate the drone. * - * This will run the terminate routine as configured on the drone (e.g. disarm and open the - * parachute). + * This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute). * * This function is non-blocking. See 'terminate' for the blocking counterpart. */ void terminate_async(const ResultCallback callback); + + /** * @brief Send command to terminate the drone. * - * This will run the terminate routine as configured on the drone (e.g. disarm and open the - * parachute). + * This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute). * * This function is blocking. See 'terminate_async' for the non-blocking counterpart. * @@ -267,6 +307,9 @@ class Action : public PluginBase { */ Result terminate() const; + + + /** * @brief Send command to kill the drone. * @@ -277,6 +320,8 @@ class Action : public PluginBase { */ void kill_async(const ResultCallback callback); + + /** * @brief Send command to kill the drone. * @@ -289,25 +334,28 @@ class Action : public PluginBase { */ Result kill() const; + + + /** * @brief Send command to return to the launch (takeoff) position and land. * - * This switches the drone into [Return - * mode](https://docs.px4.io/master/en/flight_modes/return.html) which generally means it will - * rise up to a certain altitude to clear any obstacles before heading back to the launch - * (takeoff) position and land there. + * This switches the drone into [Return mode](https://docs.px4.io/master/en/flight_modes/return.html) which + * generally means it will rise up to a certain altitude to clear any obstacles before heading + * back to the launch (takeoff) position and land there. * * This function is non-blocking. See 'return_to_launch' for the blocking counterpart. */ void return_to_launch_async(const ResultCallback callback); + + /** * @brief Send command to return to the launch (takeoff) position and land. * - * This switches the drone into [Return - * mode](https://docs.px4.io/master/en/flight_modes/return.html) which generally means it will - * rise up to a certain altitude to clear any obstacles before heading back to the launch - * (takeoff) position and land there. + * This switches the drone into [Return mode](https://docs.px4.io/master/en/flight_modes/return.html) which + * generally means it will rise up to a certain altitude to clear any obstacles before heading + * back to the launch (takeoff) position and land there. * * This function is blocking. See 'return_to_launch_async' for the non-blocking counterpart. * @@ -315,6 +363,9 @@ class Action : public PluginBase { */ Result return_to_launch() const; + + + /** * @brief Send command to move the vehicle to a specific global position. * @@ -325,12 +376,9 @@ class Action : public PluginBase { * * This function is non-blocking. See 'goto_location' for the blocking counterpart. */ - void goto_location_async( - double latitude_deg, - double longitude_deg, - float absolute_altitude_m, - float yaw_deg, - const ResultCallback callback); + void goto_location_async(double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg, const ResultCallback callback); + + /** * @brief Send command to move the vehicle to a specific global position. @@ -344,8 +392,10 @@ class Action : public PluginBase { * * @return Result of request. */ - Result goto_location( - double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg) const; + Result goto_location(double latitude_deg, double longitude_deg, float absolute_altitude_m, float yaw_deg) const; + + + /** * @brief Send command do orbit to the drone. @@ -354,14 +404,9 @@ class Action : public PluginBase { * * This function is non-blocking. See 'do_orbit' for the blocking counterpart. */ - void do_orbit_async( - float radius_m, - float velocity_ms, - OrbitYawBehavior yaw_behavior, - double latitude_deg, - double longitude_deg, - double absolute_altitude_m, - const ResultCallback callback); + void do_orbit_async(float radius_m, float velocity_ms, OrbitYawBehavior yaw_behavior, double latitude_deg, double longitude_deg, double absolute_altitude_m, const ResultCallback callback); + + /** * @brief Send command do orbit to the drone. @@ -372,13 +417,10 @@ class Action : public PluginBase { * * @return Result of request. */ - Result do_orbit( - float radius_m, - float velocity_ms, - OrbitYawBehavior yaw_behavior, - double latitude_deg, - double longitude_deg, - double absolute_altitude_m) const; + Result do_orbit(float radius_m, float velocity_ms, OrbitYawBehavior yaw_behavior, double latitude_deg, double longitude_deg, double absolute_altitude_m) const; + + + /** * @brief Send command to hold position (a.k.a. "Loiter"). @@ -393,6 +435,8 @@ class Action : public PluginBase { */ void hold_async(const ResultCallback callback); + + /** * @brief Send command to hold position (a.k.a. "Loiter"). * @@ -408,6 +452,9 @@ class Action : public PluginBase { */ Result hold() const; + + + /** * @brief Send command to set the value of an actuator. * @@ -415,6 +462,8 @@ class Action : public PluginBase { */ void set_actuator_async(int32_t index, float value, const ResultCallback callback); + + /** * @brief Send command to set the value of an actuator. * @@ -424,6 +473,9 @@ class Action : public PluginBase { */ Result set_actuator(int32_t index, float value) const; + + + /** * @brief Send command to transition the drone to fixedwing. * @@ -435,6 +487,8 @@ class Action : public PluginBase { */ void transition_to_fixedwing_async(const ResultCallback callback); + + /** * @brief Send command to transition the drone to fixedwing. * @@ -442,13 +496,15 @@ class Action : public PluginBase { * command will fail). The command will succeed if called when the vehicle * is already in fixedwing mode. * - * This function is blocking. See 'transition_to_fixedwing_async' for the non-blocking - * counterpart. + * This function is blocking. See 'transition_to_fixedwing_async' for the non-blocking counterpart. * * @return Result of request. */ Result transition_to_fixedwing() const; + + + /** * @brief Send command to transition the drone to multicopter. * @@ -460,6 +516,8 @@ class Action : public PluginBase { */ void transition_to_multicopter_async(const ResultCallback callback); + + /** * @brief Send command to transition the drone to multicopter. * @@ -467,16 +525,18 @@ class Action : public PluginBase { * command will fail). The command will succeed if called when the vehicle * is already in multicopter mode. * - * This function is blocking. See 'transition_to_multicopter_async' for the non-blocking - * counterpart. + * This function is blocking. See 'transition_to_multicopter_async' for the non-blocking counterpart. * * @return Result of request. */ Result transition_to_multicopter() const; + + + /** - * @brief Callback type for get_takeoff_altitude_async. - */ + * @brief Callback type for get_takeoff_altitude_async. + */ using GetTakeoffAltitudeCallback = std::function; /** @@ -486,6 +546,8 @@ class Action : public PluginBase { */ void get_takeoff_altitude_async(const GetTakeoffAltitudeCallback callback); + + /** * @brief Get the takeoff altitude (in meters above ground). * @@ -495,6 +557,9 @@ class Action : public PluginBase { */ std::pair get_takeoff_altitude() const; + + + /** * @brief Set takeoff altitude (in meters above ground). * @@ -502,6 +567,8 @@ class Action : public PluginBase { */ void set_takeoff_altitude_async(float altitude, const ResultCallback callback); + + /** * @brief Set takeoff altitude (in meters above ground). * @@ -511,9 +578,12 @@ class Action : public PluginBase { */ Result set_takeoff_altitude(float altitude) const; + + + /** - * @brief Callback type for get_maximum_speed_async. - */ + * @brief Callback type for get_maximum_speed_async. + */ using GetMaximumSpeedCallback = std::function; /** @@ -523,6 +593,8 @@ class Action : public PluginBase { */ void get_maximum_speed_async(const GetMaximumSpeedCallback callback); + + /** * @brief Get the vehicle maximum speed (in metres/second). * @@ -532,6 +604,9 @@ class Action : public PluginBase { */ std::pair get_maximum_speed() const; + + + /** * @brief Set vehicle maximum speed (in metres/second). * @@ -539,6 +614,8 @@ class Action : public PluginBase { */ void set_maximum_speed_async(float speed, const ResultCallback callback); + + /** * @brief Set vehicle maximum speed (in metres/second). * @@ -548,48 +625,56 @@ class Action : public PluginBase { */ Result set_maximum_speed(float speed) const; + + + /** - * @brief Callback type for get_return_to_launch_altitude_async. - */ + * @brief Callback type for get_return_to_launch_altitude_async. + */ using GetReturnToLaunchAltitudeCallback = std::function; /** * @brief Get the return to launch minimum return altitude (in meters). * - * This function is non-blocking. See 'get_return_to_launch_altitude' for the blocking - * counterpart. + * This function is non-blocking. See 'get_return_to_launch_altitude' for the blocking counterpart. */ void get_return_to_launch_altitude_async(const GetReturnToLaunchAltitudeCallback callback); + + /** * @brief Get the return to launch minimum return altitude (in meters). * - * This function is blocking. See 'get_return_to_launch_altitude_async' for the non-blocking - * counterpart. + * This function is blocking. See 'get_return_to_launch_altitude_async' for the non-blocking counterpart. * * @return Result of request. */ std::pair get_return_to_launch_altitude() const; + + + /** * @brief Set the return to launch minimum return altitude (in meters). * - * This function is non-blocking. See 'set_return_to_launch_altitude' for the blocking - * counterpart. + * This function is non-blocking. See 'set_return_to_launch_altitude' for the blocking counterpart. */ - void - set_return_to_launch_altitude_async(float relative_altitude_m, const ResultCallback callback); + void set_return_to_launch_altitude_async(float relative_altitude_m, const ResultCallback callback); + + /** * @brief Set the return to launch minimum return altitude (in meters). * - * This function is blocking. See 'set_return_to_launch_altitude_async' for the non-blocking - * counterpart. + * This function is blocking. See 'set_return_to_launch_altitude_async' for the non-blocking counterpart. * * @return Result of request. */ Result set_return_to_launch_altitude(float relative_altitude_m) const; + + + /** * @brief Set current speed. * @@ -600,6 +685,8 @@ class Action : public PluginBase { */ void set_current_speed_async(float speed_m_s, const ResultCallback callback); + + /** * @brief Set current speed. * @@ -612,6 +699,9 @@ class Action : public PluginBase { */ Result set_current_speed(float speed_m_s) const; + + + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/action_server/action_server.cpp b/src/mavsdk/plugins/action_server/action_server.cpp index 64da65111f..dd941a43c5 100644 --- a/src/mavsdk/plugins/action_server/action_server.cpp +++ b/src/mavsdk/plugins/action_server/action_server.cpp @@ -1,7 +1,6 @@ // WARNING: THIS FILE IS AUTOGENERATED! As such, it should not be edited. // Edits need to be made to the proto files -// (see -// https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/action_server/action_server.proto) +// (see https://github.com/mavlink/MAVSDK-Proto/blob/master/protos/action_server/action_server.proto) #include @@ -13,13 +12,17 @@ namespace mavsdk { using AllowableFlightModes = ActionServer::AllowableFlightModes; using ArmDisarm = ActionServer::ArmDisarm; -ActionServer::ActionServer(std::shared_ptr server_component) : - ServerPluginBase(), - _impl{std::make_unique(server_component)} -{} + + + +ActionServer::ActionServer(std::shared_ptr server_component) : ServerPluginBase(), _impl{std::make_unique(server_component)} {} + ActionServer::~ActionServer() {} + + + ActionServer::ArmDisarmHandle ActionServer::subscribe_arm_disarm(const ArmDisarmCallback& callback) { return _impl->subscribe_arm_disarm(callback); @@ -29,9 +32,14 @@ void ActionServer::unsubscribe_arm_disarm(ArmDisarmHandle handle) { _impl->unsubscribe_arm_disarm(handle); } + + + -ActionServer::FlightModeChangeHandle -ActionServer::subscribe_flight_mode_change(const FlightModeChangeCallback& callback) + + + +ActionServer::FlightModeChangeHandle ActionServer::subscribe_flight_mode_change(const FlightModeChangeCallback& callback) { return _impl->subscribe_flight_mode_change(callback); } @@ -40,7 +48,13 @@ void ActionServer::unsubscribe_flight_mode_change(FlightModeChangeHandle handle) { _impl->unsubscribe_flight_mode_change(handle); } + + + + + + ActionServer::TakeoffHandle ActionServer::subscribe_takeoff(const TakeoffCallback& callback) { return _impl->subscribe_takeoff(callback); @@ -50,7 +64,13 @@ void ActionServer::unsubscribe_takeoff(TakeoffHandle handle) { _impl->unsubscribe_takeoff(handle); } + + + + + + ActionServer::LandHandle ActionServer::subscribe_land(const LandCallback& callback) { return _impl->subscribe_land(callback); @@ -60,7 +80,13 @@ void ActionServer::unsubscribe_land(LandHandle handle) { _impl->unsubscribe_land(handle); } + + + + + + ActionServer::RebootHandle ActionServer::subscribe_reboot(const RebootCallback& callback) { return _impl->subscribe_reboot(callback); @@ -70,7 +96,13 @@ void ActionServer::unsubscribe_reboot(RebootHandle handle) { _impl->unsubscribe_reboot(handle); } + + + + + + ActionServer::ShutdownHandle ActionServer::subscribe_shutdown(const ShutdownCallback& callback) { return _impl->subscribe_shutdown(callback); @@ -80,7 +112,13 @@ void ActionServer::unsubscribe_shutdown(ShutdownHandle handle) { _impl->unsubscribe_shutdown(handle); } + + + + + + ActionServer::TerminateHandle ActionServer::subscribe_terminate(const TerminateCallback& callback) { return _impl->subscribe_terminate(callback); @@ -90,46 +128,70 @@ void ActionServer::unsubscribe_terminate(TerminateHandle handle) { _impl->unsubscribe_terminate(handle); } + + + + + + + ActionServer::Result ActionServer::set_allow_takeoff(bool allow_takeoff) const { return _impl->set_allow_takeoff(allow_takeoff); } + + + + ActionServer::Result ActionServer::set_armable(bool armable, bool force_armable) const { return _impl->set_armable(armable, force_armable); } + + + + ActionServer::Result ActionServer::set_disarmable(bool disarmable, bool force_disarmable) const { return _impl->set_disarmable(disarmable, force_disarmable); } -ActionServer::Result -ActionServer::set_allowable_flight_modes(AllowableFlightModes flight_modes) const + + + + +ActionServer::Result ActionServer::set_allowable_flight_modes(AllowableFlightModes flight_modes) const { return _impl->set_allowable_flight_modes(flight_modes); } + + + + ActionServer::AllowableFlightModes ActionServer::get_allowable_flight_modes() const { return _impl->get_allowable_flight_modes(); } -bool operator==( - const ActionServer::AllowableFlightModes& lhs, const ActionServer::AllowableFlightModes& rhs) + + +bool operator==(const ActionServer::AllowableFlightModes& lhs, const ActionServer::AllowableFlightModes& rhs) { - return (rhs.can_auto_mode == lhs.can_auto_mode) && - (rhs.can_guided_mode == lhs.can_guided_mode) && - (rhs.can_stabilize_mode == lhs.can_stabilize_mode); + return + (rhs.can_auto_mode == lhs.can_auto_mode) && + (rhs.can_guided_mode == lhs.can_guided_mode) && + (rhs.can_stabilize_mode == lhs.can_stabilize_mode); } -std::ostream& -operator<<(std::ostream& str, ActionServer::AllowableFlightModes const& allowable_flight_modes) +std::ostream& operator<<(std::ostream& str, ActionServer::AllowableFlightModes const& allowable_flight_modes) { str << std::setprecision(15); - str << "allowable_flight_modes:" << '\n' << "{\n"; + str << "allowable_flight_modes:" << '\n' + << "{\n"; str << " can_auto_mode: " << allowable_flight_modes.can_auto_mode << '\n'; str << " can_guided_mode: " << allowable_flight_modes.can_guided_mode << '\n'; str << " can_stabilize_mode: " << allowable_flight_modes.can_stabilize_mode << '\n'; @@ -137,21 +199,27 @@ operator<<(std::ostream& str, ActionServer::AllowableFlightModes const& allowabl return str; } + bool operator==(const ActionServer::ArmDisarm& lhs, const ActionServer::ArmDisarm& rhs) { - return (rhs.arm == lhs.arm) && (rhs.force == lhs.force); + return + (rhs.arm == lhs.arm) && + (rhs.force == lhs.force); } std::ostream& operator<<(std::ostream& str, ActionServer::ArmDisarm const& arm_disarm) { str << std::setprecision(15); - str << "arm_disarm:" << '\n' << "{\n"; + str << "arm_disarm:" << '\n' + << "{\n"; str << " arm: " << arm_disarm.arm << '\n'; str << " force: " << arm_disarm.force << '\n'; str << '}'; return str; } + + std::ostream& operator<<(std::ostream& str, ActionServer::Result const& result) { switch (result) { @@ -186,6 +254,8 @@ std::ostream& operator<<(std::ostream& str, ActionServer::Result const& result) } } + + std::ostream& operator<<(std::ostream& str, ActionServer::FlightMode const& flight_mode) { switch (flight_mode) { @@ -222,4 +292,5 @@ std::ostream& operator<<(std::ostream& str, ActionServer::FlightMode const& flig } } + } // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/action_server/include/plugins/action_server/action_server.h b/src/mavsdk/plugins/action_server/include/plugins/action_server/action_server.h index f2a3d750d8..bc79d38398 100644 --- a/src/mavsdk/plugins/action_server/include/plugins/action_server/action_server.h +++ b/src/mavsdk/plugins/action_server/include/plugins/action_server/action_server.h @@ -13,12 +13,14 @@ #include #include + #include "server_plugin_base.h" #include "handle.h" namespace mavsdk { + class ServerComponent; class ActionServerImpl; @@ -27,6 +29,7 @@ class ActionServerImpl; */ class ActionServer : public ServerPluginBase { public: + /** * @brief Constructor. Creates the plugin for a ServerComponent instance. * @@ -40,11 +43,13 @@ class ActionServer : public ServerPluginBase { */ explicit ActionServer(std::shared_ptr server_component); + /** * @brief Destructor (internal use only). */ ~ActionServer() override; + /** * @brief Flight modes. * @@ -75,11 +80,15 @@ class ActionServer : public ServerPluginBase { */ friend std::ostream& operator<<(std::ostream& str, ActionServer::FlightMode const& flight_mode); + + + /** * @brief State to check if the vehicle can transition to * respective flightmodes */ struct AllowableFlightModes { + bool can_auto_mode{}; /**< @brief Auto/mission mode */ bool can_guided_mode{}; /**< @brief Guided mode */ bool can_stabilize_mode{}; /**< @brief Stabilize mode */ @@ -90,22 +99,23 @@ class ActionServer : public ServerPluginBase { * * @return `true` if items are equal. */ - friend bool operator==( - const ActionServer::AllowableFlightModes& lhs, - const ActionServer::AllowableFlightModes& rhs); + friend bool operator==(const ActionServer::AllowableFlightModes& lhs, const ActionServer::AllowableFlightModes& rhs); /** * @brief Stream operator to print information about a `ActionServer::AllowableFlightModes`. * * @return A reference to the stream. */ - friend std::ostream& - operator<<(std::ostream& str, ActionServer::AllowableFlightModes const& allowable_flight_modes); + friend std::ostream& operator<<(std::ostream& str, ActionServer::AllowableFlightModes const& allowable_flight_modes); + + + /** * @brief Arming message type */ struct ArmDisarm { + bool arm{}; /**< @brief Should vehicle arm */ bool force{}; /**< @brief Should arm override pre-flight checks */ }; @@ -124,6 +134,10 @@ class ActionServer : public ServerPluginBase { */ friend std::ostream& operator<<(std::ostream& str, ActionServer::ArmDisarm const& arm_disarm); + + + + /** * @brief Possible results returned for action requests. */ @@ -134,15 +148,13 @@ class ActionServer : public ServerPluginBase { ConnectionError, /**< @brief Connection error. */ Busy, /**< @brief Vehicle is busy. */ CommandDenied, /**< @brief Command refused by vehicle. */ - CommandDeniedLandedStateUnknown, /**< @brief Command refused because landed state is - unknown. */ + CommandDeniedLandedStateUnknown, /**< @brief Command refused because landed state is unknown. */ CommandDeniedNotLanded, /**< @brief Command refused because vehicle not landed. */ Timeout, /**< @brief Request timed out. */ VtolTransitionSupportUnknown, /**< @brief Hybrid/VTOL transition support is unknown. */ NoVtolTransitionSupport, /**< @brief Vehicle does not support hybrid/VTOL transitions. */ ParameterError, /**< @brief Error getting or setting parameter. */ - Next, /**< @brief Intermediate message showing progress or instructions on the next steps. - */ + Next, /**< @brief Intermediate message showing progress or instructions on the next steps. */ }; /** @@ -152,11 +164,18 @@ class ActionServer : public ServerPluginBase { */ friend std::ostream& operator<<(std::ostream& str, ActionServer::Result const& result); + + /** * @brief Callback type for asynchronous ActionServer calls. */ using ResultCallback = std::function; + + + + + /** * @brief Callback type for subscribe_arm_disarm. */ @@ -177,6 +196,15 @@ class ActionServer : public ServerPluginBase { */ void unsubscribe_arm_disarm(ArmDisarmHandle handle); + + + + + + + + + /** * @brief Callback type for subscribe_flight_mode_change. */ @@ -197,6 +225,15 @@ class ActionServer : public ServerPluginBase { */ void unsubscribe_flight_mode_change(FlightModeChangeHandle handle); + + + + + + + + + /** * @brief Callback type for subscribe_takeoff. */ @@ -217,6 +254,15 @@ class ActionServer : public ServerPluginBase { */ void unsubscribe_takeoff(TakeoffHandle handle); + + + + + + + + + /** * @brief Callback type for subscribe_land. */ @@ -237,6 +283,15 @@ class ActionServer : public ServerPluginBase { */ void unsubscribe_land(LandHandle handle); + + + + + + + + + /** * @brief Callback type for subscribe_reboot. */ @@ -257,6 +312,15 @@ class ActionServer : public ServerPluginBase { */ void unsubscribe_reboot(RebootHandle handle); + + + + + + + + + /** * @brief Callback type for subscribe_shutdown. */ @@ -277,6 +341,15 @@ class ActionServer : public ServerPluginBase { */ void unsubscribe_shutdown(ShutdownHandle handle); + + + + + + + + + /** * @brief Callback type for subscribe_terminate. */ @@ -297,6 +370,15 @@ class ActionServer : public ServerPluginBase { */ void unsubscribe_terminate(TerminateHandle handle); + + + + + + + + + /** * @brief Can the vehicle takeoff * @@ -306,6 +388,11 @@ class ActionServer : public ServerPluginBase { */ Result set_allow_takeoff(bool allow_takeoff) const; + + + + + /** * @brief Can the vehicle arm when requested * @@ -315,6 +402,11 @@ class ActionServer : public ServerPluginBase { */ Result set_armable(bool armable, bool force_armable) const; + + + + + /** * @brief Can the vehicle disarm when requested * @@ -324,6 +416,11 @@ class ActionServer : public ServerPluginBase { */ Result set_disarmable(bool disarmable, bool force_disarmable) const; + + + + + /** * @brief Set which modes the vehicle can transition to (Manual always allowed) * @@ -333,6 +430,11 @@ class ActionServer : public ServerPluginBase { */ Result set_allowable_flight_modes(AllowableFlightModes flight_modes) const; + + + + + /** * @brief Get which modes the vehicle can transition to (Manual always allowed) * @@ -342,6 +444,9 @@ class ActionServer : public ServerPluginBase { */ ActionServer::AllowableFlightModes get_allowable_flight_modes() const; + + + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/calibration/calibration.cpp b/src/mavsdk/plugins/calibration/calibration.cpp index 767a6dcb54..62a72a4f31 100644 --- a/src/mavsdk/plugins/calibration/calibration.cpp +++ b/src/mavsdk/plugins/calibration/calibration.cpp @@ -9,51 +9,85 @@ namespace mavsdk { + using ProgressData = Calibration::ProgressData; -Calibration::Calibration(System& system) : - PluginBase(), - _impl{std::make_unique(system)} -{} -Calibration::Calibration(std::shared_ptr system) : - PluginBase(), - _impl{std::make_unique(system)} -{} + +Calibration::Calibration(System& system) : PluginBase(), _impl{std::make_unique(system)} {} + +Calibration::Calibration(std::shared_ptr system) : PluginBase(), _impl{std::make_unique(system)} {} + Calibration::~Calibration() {} + + + void Calibration::calibrate_gyro_async(const CalibrateGyroCallback& callback) { _impl->calibrate_gyro_async(callback); } + + + + + + void Calibration::calibrate_accelerometer_async(const CalibrateAccelerometerCallback& callback) { _impl->calibrate_accelerometer_async(callback); } + + + + + + void Calibration::calibrate_magnetometer_async(const CalibrateMagnetometerCallback& callback) { _impl->calibrate_magnetometer_async(callback); } + + + + + + void Calibration::calibrate_level_horizon_async(const CalibrateLevelHorizonCallback& callback) { _impl->calibrate_level_horizon_async(callback); } + -void Calibration::calibrate_gimbal_accelerometer_async( - const CalibrateGimbalAccelerometerCallback& callback) + + + + + +void Calibration::calibrate_gimbal_accelerometer_async(const CalibrateGimbalAccelerometerCallback& callback) { _impl->calibrate_gimbal_accelerometer_async(callback); } + + + + + + + Calibration::Result Calibration::cancel() const { return _impl->cancel(); } + + + std::ostream& operator<<(std::ostream& str, Calibration::Result const& result) { switch (result) { @@ -86,18 +120,21 @@ std::ostream& operator<<(std::ostream& str, Calibration::Result const& result) } } + bool operator==(const Calibration::ProgressData& lhs, const Calibration::ProgressData& rhs) { - return (rhs.has_progress == lhs.has_progress) && - ((std::isnan(rhs.progress) && std::isnan(lhs.progress)) || - rhs.progress == lhs.progress) && - (rhs.has_status_text == lhs.has_status_text) && (rhs.status_text == lhs.status_text); + return + (rhs.has_progress == lhs.has_progress) && + ((std::isnan(rhs.progress) && std::isnan(lhs.progress)) || rhs.progress == lhs.progress) && + (rhs.has_status_text == lhs.has_status_text) && + (rhs.status_text == lhs.status_text); } std::ostream& operator<<(std::ostream& str, Calibration::ProgressData const& progress_data) { str << std::setprecision(15); - str << "progress_data:" << '\n' << "{\n"; + str << "progress_data:" << '\n' + << "{\n"; str << " has_progress: " << progress_data.has_progress << '\n'; str << " progress: " << progress_data.progress << '\n'; str << " has_status_text: " << progress_data.has_status_text << '\n'; @@ -106,4 +143,7 @@ std::ostream& operator<<(std::ostream& str, Calibration::ProgressData const& pro return str; } + + + } // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/calibration/include/plugins/calibration/calibration.h b/src/mavsdk/plugins/calibration/include/plugins/calibration/calibration.h index a3e6529eed..cd72bbbc97 100644 --- a/src/mavsdk/plugins/calibration/include/plugins/calibration/calibration.h +++ b/src/mavsdk/plugins/calibration/include/plugins/calibration/calibration.h @@ -13,20 +13,22 @@ #include #include + #include "plugin_base.h" #include "handle.h" namespace mavsdk { -class System; -class CalibrationImpl; + +class System;class CalibrationImpl; /** * @brief Enable to calibrate sensors of a drone such as gyro, accelerometer, and magnetometer. */ class Calibration : public PluginBase { public: + /** * @brief Constructor. Creates the plugin for a specific System. * @@ -53,19 +55,24 @@ class Calibration : public PluginBase { */ explicit Calibration(std::shared_ptr system); // new + /** * @brief Destructor (internal use only). */ ~Calibration() override; + + + + + /** * @brief Possible results returned for calibration commands */ enum class Result { Unknown, /**< @brief Unknown result. */ Success, /**< @brief The calibration succeeded. */ - Next, /**< @brief Intermediate message showing progress or instructions on the next steps. - */ + Next, /**< @brief Intermediate message showing progress or instructions on the next steps. */ Failed, /**< @brief Calibration failed. */ NoSystem, /**< @brief No system is connected. */ ConnectionError, /**< @brief Connection error. */ @@ -84,17 +91,20 @@ class Calibration : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Calibration::Result const& result); + + + + /** * @brief Progress data coming from calibration. * * Can be a progress percentage, or an instruction text. */ struct ProgressData { - bool has_progress{ - false}; /**< @brief Whether this ProgressData contains a 'progress' status or not */ + + bool has_progress{false}; /**< @brief Whether this ProgressData contains a 'progress' status or not */ float progress{float(NAN)}; /**< @brief Progress (percentage) */ - bool has_status_text{ - false}; /**< @brief Whether this ProgressData contains a 'status_text' or not */ + bool has_status_text{false}; /**< @brief Whether this ProgressData contains a 'status_text' or not */ std::string status_text{}; /**< @brief Instruction text */ }; @@ -103,22 +113,25 @@ class Calibration : public PluginBase { * * @return `true` if items are equal. */ - friend bool - operator==(const Calibration::ProgressData& lhs, const Calibration::ProgressData& rhs); + friend bool operator==(const Calibration::ProgressData& lhs, const Calibration::ProgressData& rhs); /** * @brief Stream operator to print information about a `Calibration::ProgressData`. * * @return A reference to the stream. */ - friend std::ostream& - operator<<(std::ostream& str, Calibration::ProgressData const& progress_data); + friend std::ostream& operator<<(std::ostream& str, Calibration::ProgressData const& progress_data); + /** * @brief Callback type for asynchronous Calibration calls. */ using ResultCallback = std::function; + + + + /** * @brief Callback type for calibrate_gyro_async. */ @@ -129,6 +142,14 @@ class Calibration : public PluginBase { */ void calibrate_gyro_async(const CalibrateGyroCallback& callback); + + + + + + + + /** * @brief Callback type for calibrate_accelerometer_async. */ @@ -139,6 +160,14 @@ class Calibration : public PluginBase { */ void calibrate_accelerometer_async(const CalibrateAccelerometerCallback& callback); + + + + + + + + /** * @brief Callback type for calibrate_magnetometer_async. */ @@ -149,6 +178,14 @@ class Calibration : public PluginBase { */ void calibrate_magnetometer_async(const CalibrateMagnetometerCallback& callback); + + + + + + + + /** * @brief Callback type for calibrate_level_horizon_async. */ @@ -159,6 +196,14 @@ class Calibration : public PluginBase { */ void calibrate_level_horizon_async(const CalibrateLevelHorizonCallback& callback); + + + + + + + + /** * @brief Callback type for calibrate_gimbal_accelerometer_async. */ @@ -169,6 +214,15 @@ class Calibration : public PluginBase { */ void calibrate_gimbal_accelerometer_async(const CalibrateGimbalAccelerometerCallback& callback); + + + + + + + + + /** * @brief Cancel ongoing calibration process. * @@ -178,6 +232,9 @@ class Calibration : public PluginBase { */ Result cancel() const; + + + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/camera/camera.cpp b/src/mavsdk/plugins/camera/camera.cpp index eaeaa9cf45..64061beec3 100644 --- a/src/mavsdk/plugins/camera/camera.cpp +++ b/src/mavsdk/plugins/camera/camera.cpp @@ -9,6 +9,7 @@ namespace mavsdk { + using Position = Camera::Position; using Quaternion = Camera::Quaternion; using EulerAngle = Camera::EulerAngle; @@ -21,106 +22,148 @@ using Setting = Camera::Setting; using SettingOptions = Camera::SettingOptions; using Information = Camera::Information; + + Camera::Camera(System& system) : PluginBase(), _impl{std::make_unique(system)} {} -Camera::Camera(std::shared_ptr system) : - PluginBase(), - _impl{std::make_unique(system)} -{} +Camera::Camera(std::shared_ptr system) : PluginBase(), _impl{std::make_unique(system)} {} + Camera::~Camera() {} + + void Camera::prepare_async(const ResultCallback callback) { _impl->prepare_async(callback); } + + Camera::Result Camera::prepare() const { return _impl->prepare(); } + + void Camera::take_photo_async(const ResultCallback callback) { _impl->take_photo_async(callback); } + + Camera::Result Camera::take_photo() const { return _impl->take_photo(); } + + void Camera::start_photo_interval_async(float interval_s, const ResultCallback callback) { _impl->start_photo_interval_async(interval_s, callback); } + + Camera::Result Camera::start_photo_interval(float interval_s) const { return _impl->start_photo_interval(interval_s); } + + void Camera::stop_photo_interval_async(const ResultCallback callback) { _impl->stop_photo_interval_async(callback); } + + Camera::Result Camera::stop_photo_interval() const { return _impl->stop_photo_interval(); } + + void Camera::start_video_async(const ResultCallback callback) { _impl->start_video_async(callback); } + + Camera::Result Camera::start_video() const { return _impl->start_video(); } + + void Camera::stop_video_async(const ResultCallback callback) { _impl->stop_video_async(callback); } + + Camera::Result Camera::stop_video() const { return _impl->stop_video(); } + + + + Camera::Result Camera::start_video_streaming() const { return _impl->start_video_streaming(); } + + + + Camera::Result Camera::stop_video_streaming() const { return _impl->stop_video_streaming(); } + + void Camera::set_mode_async(Mode mode, const ResultCallback callback) { _impl->set_mode_async(mode, callback); } + + Camera::Result Camera::set_mode(Mode mode) const { return _impl->set_mode(mode); } + + void Camera::list_photos_async(PhotosRange photos_range, const ListPhotosCallback callback) { _impl->list_photos_async(photos_range, callback); } -std::pair> -Camera::list_photos(PhotosRange photos_range) const + + +std::pair> Camera::list_photos(PhotosRange photos_range) const { return _impl->list_photos(photos_range); } + + + Camera::ModeHandle Camera::subscribe_mode(const ModeCallback& callback) { return _impl->subscribe_mode(callback); @@ -130,12 +173,20 @@ void Camera::unsubscribe_mode(ModeHandle handle) { _impl->unsubscribe_mode(handle); } + + + + -Camera::Mode Camera::mode() const +Camera::Mode +Camera::mode() const { return _impl->mode(); } + + + Camera::InformationHandle Camera::subscribe_information(const InformationCallback& callback) { return _impl->subscribe_information(callback); @@ -145,14 +196,21 @@ void Camera::unsubscribe_information(InformationHandle handle) { _impl->unsubscribe_information(handle); } + + + -Camera::Information Camera::information() const + +Camera::Information +Camera::information() const { return _impl->information(); } -Camera::VideoStreamInfoHandle -Camera::subscribe_video_stream_info(const VideoStreamInfoCallback& callback) + + + +Camera::VideoStreamInfoHandle Camera::subscribe_video_stream_info(const VideoStreamInfoCallback& callback) { return _impl->subscribe_video_stream_info(callback); } @@ -161,12 +219,20 @@ void Camera::unsubscribe_video_stream_info(VideoStreamInfoHandle handle) { _impl->unsubscribe_video_stream_info(handle); } + -Camera::VideoStreamInfo Camera::video_stream_info() const + + + +Camera::VideoStreamInfo +Camera::video_stream_info() const { return _impl->video_stream_info(); } + + + Camera::CaptureInfoHandle Camera::subscribe_capture_info(const CaptureInfoCallback& callback) { return _impl->subscribe_capture_info(callback); @@ -176,7 +242,13 @@ void Camera::unsubscribe_capture_info(CaptureInfoHandle handle) { _impl->unsubscribe_capture_info(handle); } + + + + + + Camera::StatusHandle Camera::subscribe_status(const StatusCallback& callback) { return _impl->subscribe_status(callback); @@ -186,14 +258,21 @@ void Camera::unsubscribe_status(StatusHandle handle) { _impl->unsubscribe_status(handle); } + + + -Camera::Status Camera::status() const + +Camera::Status +Camera::status() const { return _impl->status(); } -Camera::CurrentSettingsHandle -Camera::subscribe_current_settings(const CurrentSettingsCallback& callback) + + + +Camera::CurrentSettingsHandle Camera::subscribe_current_settings(const CurrentSettingsCallback& callback) { return _impl->subscribe_current_settings(callback); } @@ -202,9 +281,14 @@ void Camera::unsubscribe_current_settings(CurrentSettingsHandle handle) { _impl->unsubscribe_current_settings(handle); } + -Camera::PossibleSettingOptionsHandle -Camera::subscribe_possible_setting_options(const PossibleSettingOptionsCallback& callback) + + + + + +Camera::PossibleSettingOptionsHandle Camera::subscribe_possible_setting_options(const PossibleSettingOptionsCallback& callback) { return _impl->subscribe_possible_setting_options(callback); } @@ -213,47 +297,71 @@ void Camera::unsubscribe_possible_setting_options(PossibleSettingOptionsHandle h { _impl->unsubscribe_possible_setting_options(handle); } + + + + -std::vector Camera::possible_setting_options() const +std::vector +Camera::possible_setting_options() const { return _impl->possible_setting_options(); } + + void Camera::set_setting_async(Setting setting, const ResultCallback callback) { _impl->set_setting_async(setting, callback); } + + Camera::Result Camera::set_setting(Setting setting) const { return _impl->set_setting(setting); } + + void Camera::get_setting_async(Setting setting, const GetSettingCallback callback) { _impl->get_setting_async(setting, callback); } + + std::pair Camera::get_setting(Setting setting) const { return _impl->get_setting(setting); } + + void Camera::format_storage_async(const ResultCallback callback) { _impl->format_storage_async(callback); } + + Camera::Result Camera::format_storage() const { return _impl->format_storage(); } + + + + Camera::Result Camera::select_camera(int32_t camera_id) const { return _impl->select_camera(camera_id); } + + + std::ostream& operator<<(std::ostream& str, Camera::Result const& result) { switch (result) { @@ -275,27 +383,28 @@ std::ostream& operator<<(std::ostream& str, Camera::Result const& result) return str << "Wrong Argument"; case Camera::Result::NoSystem: return str << "No System"; + case Camera::Result::ProtocolUnsupported: + return str << "Protocol Unsupported"; default: return str << "Unknown"; } } + bool operator==(const Camera::Position& lhs, const Camera::Position& rhs) { - return ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) || - rhs.latitude_deg == lhs.latitude_deg) && - ((std::isnan(rhs.longitude_deg) && std::isnan(lhs.longitude_deg)) || - rhs.longitude_deg == lhs.longitude_deg) && - ((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) || - rhs.absolute_altitude_m == lhs.absolute_altitude_m) && - ((std::isnan(rhs.relative_altitude_m) && std::isnan(lhs.relative_altitude_m)) || - rhs.relative_altitude_m == lhs.relative_altitude_m); + return + ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) || rhs.latitude_deg == lhs.latitude_deg) && + ((std::isnan(rhs.longitude_deg) && std::isnan(lhs.longitude_deg)) || rhs.longitude_deg == lhs.longitude_deg) && + ((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) || rhs.absolute_altitude_m == lhs.absolute_altitude_m) && + ((std::isnan(rhs.relative_altitude_m) && std::isnan(lhs.relative_altitude_m)) || rhs.relative_altitude_m == lhs.relative_altitude_m); } std::ostream& operator<<(std::ostream& str, Camera::Position const& position) { str << std::setprecision(15); - str << "position:" << '\n' << "{\n"; + str << "position:" << '\n' + << "{\n"; str << " latitude_deg: " << position.latitude_deg << '\n'; str << " longitude_deg: " << position.longitude_deg << '\n'; str << " absolute_altitude_m: " << position.absolute_altitude_m << '\n'; @@ -304,18 +413,21 @@ std::ostream& operator<<(std::ostream& str, Camera::Position const& position) return str; } + bool operator==(const Camera::Quaternion& lhs, const Camera::Quaternion& rhs) { - return ((std::isnan(rhs.w) && std::isnan(lhs.w)) || rhs.w == lhs.w) && - ((std::isnan(rhs.x) && std::isnan(lhs.x)) || rhs.x == lhs.x) && - ((std::isnan(rhs.y) && std::isnan(lhs.y)) || rhs.y == lhs.y) && - ((std::isnan(rhs.z) && std::isnan(lhs.z)) || rhs.z == lhs.z); + return + ((std::isnan(rhs.w) && std::isnan(lhs.w)) || rhs.w == lhs.w) && + ((std::isnan(rhs.x) && std::isnan(lhs.x)) || rhs.x == lhs.x) && + ((std::isnan(rhs.y) && std::isnan(lhs.y)) || rhs.y == lhs.y) && + ((std::isnan(rhs.z) && std::isnan(lhs.z)) || rhs.z == lhs.z); } std::ostream& operator<<(std::ostream& str, Camera::Quaternion const& quaternion) { str << std::setprecision(15); - str << "quaternion:" << '\n' << "{\n"; + str << "quaternion:" << '\n' + << "{\n"; str << " w: " << quaternion.w << '\n'; str << " x: " << quaternion.x << '\n'; str << " y: " << quaternion.y << '\n'; @@ -324,19 +436,20 @@ std::ostream& operator<<(std::ostream& str, Camera::Quaternion const& quaternion return str; } + bool operator==(const Camera::EulerAngle& lhs, const Camera::EulerAngle& rhs) { - return ((std::isnan(rhs.roll_deg) && std::isnan(lhs.roll_deg)) || - rhs.roll_deg == lhs.roll_deg) && - ((std::isnan(rhs.pitch_deg) && std::isnan(lhs.pitch_deg)) || - rhs.pitch_deg == lhs.pitch_deg) && - ((std::isnan(rhs.yaw_deg) && std::isnan(lhs.yaw_deg)) || rhs.yaw_deg == lhs.yaw_deg); + return + ((std::isnan(rhs.roll_deg) && std::isnan(lhs.roll_deg)) || rhs.roll_deg == lhs.roll_deg) && + ((std::isnan(rhs.pitch_deg) && std::isnan(lhs.pitch_deg)) || rhs.pitch_deg == lhs.pitch_deg) && + ((std::isnan(rhs.yaw_deg) && std::isnan(lhs.yaw_deg)) || rhs.yaw_deg == lhs.yaw_deg); } std::ostream& operator<<(std::ostream& str, Camera::EulerAngle const& euler_angle) { str << std::setprecision(15); - str << "euler_angle:" << '\n' << "{\n"; + str << "euler_angle:" << '\n' + << "{\n"; str << " roll_deg: " << euler_angle.roll_deg << '\n'; str << " pitch_deg: " << euler_angle.pitch_deg << '\n'; str << " yaw_deg: " << euler_angle.yaw_deg << '\n'; @@ -344,18 +457,24 @@ std::ostream& operator<<(std::ostream& str, Camera::EulerAngle const& euler_angl return str; } + bool operator==(const Camera::CaptureInfo& lhs, const Camera::CaptureInfo& rhs) { - return (rhs.position == lhs.position) && (rhs.attitude_quaternion == lhs.attitude_quaternion) && - (rhs.attitude_euler_angle == lhs.attitude_euler_angle) && - (rhs.time_utc_us == lhs.time_utc_us) && (rhs.is_success == lhs.is_success) && - (rhs.index == lhs.index) && (rhs.file_url == lhs.file_url); + return + (rhs.position == lhs.position) && + (rhs.attitude_quaternion == lhs.attitude_quaternion) && + (rhs.attitude_euler_angle == lhs.attitude_euler_angle) && + (rhs.time_utc_us == lhs.time_utc_us) && + (rhs.is_success == lhs.is_success) && + (rhs.index == lhs.index) && + (rhs.file_url == lhs.file_url); } std::ostream& operator<<(std::ostream& str, Camera::CaptureInfo const& capture_info) { str << std::setprecision(15); - str << "capture_info:" << '\n' << "{\n"; + str << "capture_info:" << '\n' + << "{\n"; str << " position: " << capture_info.position << '\n'; str << " attitude_quaternion: " << capture_info.attitude_quaternion << '\n'; str << " attitude_euler_angle: " << capture_info.attitude_euler_angle << '\n'; @@ -367,26 +486,26 @@ std::ostream& operator<<(std::ostream& str, Camera::CaptureInfo const& capture_i return str; } + bool operator==(const Camera::VideoStreamSettings& lhs, const Camera::VideoStreamSettings& rhs) { - return ((std::isnan(rhs.frame_rate_hz) && std::isnan(lhs.frame_rate_hz)) || - rhs.frame_rate_hz == lhs.frame_rate_hz) && - (rhs.horizontal_resolution_pix == lhs.horizontal_resolution_pix) && - (rhs.vertical_resolution_pix == lhs.vertical_resolution_pix) && - (rhs.bit_rate_b_s == lhs.bit_rate_b_s) && (rhs.rotation_deg == lhs.rotation_deg) && - (rhs.uri == lhs.uri) && - ((std::isnan(rhs.horizontal_fov_deg) && std::isnan(lhs.horizontal_fov_deg)) || - rhs.horizontal_fov_deg == lhs.horizontal_fov_deg); + return + ((std::isnan(rhs.frame_rate_hz) && std::isnan(lhs.frame_rate_hz)) || rhs.frame_rate_hz == lhs.frame_rate_hz) && + (rhs.horizontal_resolution_pix == lhs.horizontal_resolution_pix) && + (rhs.vertical_resolution_pix == lhs.vertical_resolution_pix) && + (rhs.bit_rate_b_s == lhs.bit_rate_b_s) && + (rhs.rotation_deg == lhs.rotation_deg) && + (rhs.uri == lhs.uri) && + ((std::isnan(rhs.horizontal_fov_deg) && std::isnan(lhs.horizontal_fov_deg)) || rhs.horizontal_fov_deg == lhs.horizontal_fov_deg); } -std::ostream& -operator<<(std::ostream& str, Camera::VideoStreamSettings const& video_stream_settings) +std::ostream& operator<<(std::ostream& str, Camera::VideoStreamSettings const& video_stream_settings) { str << std::setprecision(15); - str << "video_stream_settings:" << '\n' << "{\n"; + str << "video_stream_settings:" << '\n' + << "{\n"; str << " frame_rate_hz: " << video_stream_settings.frame_rate_hz << '\n'; - str << " horizontal_resolution_pix: " << video_stream_settings.horizontal_resolution_pix - << '\n'; + str << " horizontal_resolution_pix: " << video_stream_settings.horizontal_resolution_pix << '\n'; str << " vertical_resolution_pix: " << video_stream_settings.vertical_resolution_pix << '\n'; str << " bit_rate_b_s: " << video_stream_settings.bit_rate_b_s << '\n'; str << " rotation_deg: " << video_stream_settings.rotation_deg << '\n'; @@ -396,8 +515,9 @@ operator<<(std::ostream& str, Camera::VideoStreamSettings const& video_stream_se return str; } -std::ostream& -operator<<(std::ostream& str, Camera::VideoStreamInfo::VideoStreamStatus const& video_stream_status) + + +std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo::VideoStreamStatus const& video_stream_status) { switch (video_stream_status) { case Camera::VideoStreamInfo::VideoStreamStatus::NotRunning: @@ -409,8 +529,7 @@ operator<<(std::ostream& str, Camera::VideoStreamInfo::VideoStreamStatus const& } } -std::ostream& operator<<( - std::ostream& str, Camera::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum) +std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum) { switch (video_stream_spectrum) { case Camera::VideoStreamInfo::VideoStreamSpectrum::Unknown: @@ -425,14 +544,17 @@ std::ostream& operator<<( } bool operator==(const Camera::VideoStreamInfo& lhs, const Camera::VideoStreamInfo& rhs) { - return (rhs.settings == lhs.settings) && (rhs.status == lhs.status) && - (rhs.spectrum == lhs.spectrum); + return + (rhs.settings == lhs.settings) && + (rhs.status == lhs.status) && + (rhs.spectrum == lhs.spectrum); } std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo const& video_stream_info) { str << std::setprecision(15); - str << "video_stream_info:" << '\n' << "{\n"; + str << "video_stream_info:" << '\n' + << "{\n"; str << " settings: " << video_stream_info.settings << '\n'; str << " status: " << video_stream_info.status << '\n'; str << " spectrum: " << video_stream_info.spectrum << '\n'; @@ -440,6 +562,8 @@ std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo const& video return str; } + + std::ostream& operator<<(std::ostream& str, Camera::Status::StorageStatus const& storage_status) { switch (storage_status) { @@ -477,24 +601,24 @@ std::ostream& operator<<(std::ostream& str, Camera::Status::StorageType const& s } bool operator==(const Camera::Status& lhs, const Camera::Status& rhs) { - return (rhs.video_on == lhs.video_on) && (rhs.photo_interval_on == lhs.photo_interval_on) && - ((std::isnan(rhs.used_storage_mib) && std::isnan(lhs.used_storage_mib)) || - rhs.used_storage_mib == lhs.used_storage_mib) && - ((std::isnan(rhs.available_storage_mib) && std::isnan(lhs.available_storage_mib)) || - rhs.available_storage_mib == lhs.available_storage_mib) && - ((std::isnan(rhs.total_storage_mib) && std::isnan(lhs.total_storage_mib)) || - rhs.total_storage_mib == lhs.total_storage_mib) && - ((std::isnan(rhs.recording_time_s) && std::isnan(lhs.recording_time_s)) || - rhs.recording_time_s == lhs.recording_time_s) && - (rhs.media_folder_name == lhs.media_folder_name) && - (rhs.storage_status == lhs.storage_status) && (rhs.storage_id == lhs.storage_id) && - (rhs.storage_type == lhs.storage_type); + return + (rhs.video_on == lhs.video_on) && + (rhs.photo_interval_on == lhs.photo_interval_on) && + ((std::isnan(rhs.used_storage_mib) && std::isnan(lhs.used_storage_mib)) || rhs.used_storage_mib == lhs.used_storage_mib) && + ((std::isnan(rhs.available_storage_mib) && std::isnan(lhs.available_storage_mib)) || rhs.available_storage_mib == lhs.available_storage_mib) && + ((std::isnan(rhs.total_storage_mib) && std::isnan(lhs.total_storage_mib)) || rhs.total_storage_mib == lhs.total_storage_mib) && + ((std::isnan(rhs.recording_time_s) && std::isnan(lhs.recording_time_s)) || rhs.recording_time_s == lhs.recording_time_s) && + (rhs.media_folder_name == lhs.media_folder_name) && + (rhs.storage_status == lhs.storage_status) && + (rhs.storage_id == lhs.storage_id) && + (rhs.storage_type == lhs.storage_type); } std::ostream& operator<<(std::ostream& str, Camera::Status const& status) { str << std::setprecision(15); - str << "status:" << '\n' << "{\n"; + str << "status:" << '\n' + << "{\n"; str << " video_on: " << status.video_on << '\n'; str << " photo_interval_on: " << status.photo_interval_on << '\n'; str << " used_storage_mib: " << status.used_storage_mib << '\n'; @@ -509,32 +633,40 @@ std::ostream& operator<<(std::ostream& str, Camera::Status const& status) return str; } + bool operator==(const Camera::Option& lhs, const Camera::Option& rhs) { - return (rhs.option_id == lhs.option_id) && (rhs.option_description == lhs.option_description); + return + (rhs.option_id == lhs.option_id) && + (rhs.option_description == lhs.option_description); } std::ostream& operator<<(std::ostream& str, Camera::Option const& option) { str << std::setprecision(15); - str << "option:" << '\n' << "{\n"; + str << "option:" << '\n' + << "{\n"; str << " option_id: " << option.option_id << '\n'; str << " option_description: " << option.option_description << '\n'; str << '}'; return str; } + bool operator==(const Camera::Setting& lhs, const Camera::Setting& rhs) { - return (rhs.setting_id == lhs.setting_id) && - (rhs.setting_description == lhs.setting_description) && (rhs.option == lhs.option) && - (rhs.is_range == lhs.is_range); + return + (rhs.setting_id == lhs.setting_id) && + (rhs.setting_description == lhs.setting_description) && + (rhs.option == lhs.option) && + (rhs.is_range == lhs.is_range); } std::ostream& operator<<(std::ostream& str, Camera::Setting const& setting) { str << std::setprecision(15); - str << "setting:" << '\n' << "{\n"; + str << "setting:" << '\n' + << "{\n"; str << " setting_id: " << setting.setting_id << '\n'; str << " setting_description: " << setting.setting_description << '\n'; str << " option: " << setting.option << '\n'; @@ -543,17 +675,21 @@ std::ostream& operator<<(std::ostream& str, Camera::Setting const& setting) return str; } + bool operator==(const Camera::SettingOptions& lhs, const Camera::SettingOptions& rhs) { - return (rhs.setting_id == lhs.setting_id) && - (rhs.setting_description == lhs.setting_description) && (rhs.options == lhs.options) && - (rhs.is_range == lhs.is_range); + return + (rhs.setting_id == lhs.setting_id) && + (rhs.setting_description == lhs.setting_description) && + (rhs.options == lhs.options) && + (rhs.is_range == lhs.is_range); } std::ostream& operator<<(std::ostream& str, Camera::SettingOptions const& setting_options) { str << std::setprecision(15); - str << "setting_options:" << '\n' << "{\n"; + str << "setting_options:" << '\n' + << "{\n"; str << " setting_id: " << setting_options.setting_id << '\n'; str << " setting_description: " << setting_options.setting_description << '\n'; str << " options: ["; @@ -566,24 +702,24 @@ std::ostream& operator<<(std::ostream& str, Camera::SettingOptions const& settin return str; } + bool operator==(const Camera::Information& lhs, const Camera::Information& rhs) { - return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && - ((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) || - rhs.focal_length_mm == lhs.focal_length_mm) && - ((std::isnan(rhs.horizontal_sensor_size_mm) && - std::isnan(lhs.horizontal_sensor_size_mm)) || - rhs.horizontal_sensor_size_mm == lhs.horizontal_sensor_size_mm) && - ((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) || - rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) && - (rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) && - (rhs.vertical_resolution_px == lhs.vertical_resolution_px); + return + (rhs.vendor_name == lhs.vendor_name) && + (rhs.model_name == lhs.model_name) && + ((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) || rhs.focal_length_mm == lhs.focal_length_mm) && + ((std::isnan(rhs.horizontal_sensor_size_mm) && std::isnan(lhs.horizontal_sensor_size_mm)) || rhs.horizontal_sensor_size_mm == lhs.horizontal_sensor_size_mm) && + ((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) || rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) && + (rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) && + (rhs.vertical_resolution_px == lhs.vertical_resolution_px); } std::ostream& operator<<(std::ostream& str, Camera::Information const& information) { str << std::setprecision(15); - str << "information:" << '\n' << "{\n"; + str << "information:" << '\n' + << "{\n"; str << " vendor_name: " << information.vendor_name << '\n'; str << " model_name: " << information.model_name << '\n'; str << " focal_length_mm: " << information.focal_length_mm << '\n'; @@ -595,6 +731,8 @@ std::ostream& operator<<(std::ostream& str, Camera::Information const& informati return str; } + + std::ostream& operator<<(std::ostream& str, Camera::Mode const& mode) { switch (mode) { @@ -621,4 +759,5 @@ std::ostream& operator<<(std::ostream& str, Camera::PhotosRange const& photos_ra } } + } // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index 979d5d7e13..c035fce014 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -13,14 +13,15 @@ #include #include + #include "plugin_base.h" #include "handle.h" namespace mavsdk { -class System; -class CameraImpl; + +class System;class CameraImpl; /** * @brief Can be used to manage cameras that implement the MAVLink @@ -33,6 +34,7 @@ class CameraImpl; */ class Camera : public PluginBase { public: + /** * @brief Constructor. Creates the plugin for a specific System. * @@ -59,11 +61,13 @@ class Camera : public PluginBase { */ explicit Camera(std::shared_ptr system); // new + /** * @brief Destructor (internal use only). */ ~Camera() override; + /** * @brief Camera mode type. */ @@ -95,6 +99,10 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::PhotosRange const& photos_range); + + + + /** * @brief Possible results returned for camera commands */ @@ -108,6 +116,7 @@ class Camera : public PluginBase { Timeout, /**< @brief Command timed out. */ WrongArgument, /**< @brief Command has wrong argument(s). */ NoSystem, /**< @brief No system connected. */ + ProtocolUnsupported, /**< @brief Definition file protocol not supported. */ }; /** @@ -117,10 +126,15 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::Result const& result); + + + + /** * @brief Position type in global coordinates. */ struct Position { + double latitude_deg{}; /**< @brief Latitude in degrees (range: -90 to +90) */ double longitude_deg{}; /**< @brief Longitude in degrees (range: -180 to +180) */ float absolute_altitude_m{}; /**< @brief Altitude AMSL (above mean sea level) in metres */ @@ -141,6 +155,9 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::Position const& position); + + + /** * @brief Quaternion type. * @@ -152,6 +169,7 @@ class Camera : public PluginBase { * For more info see: https://en.wikipedia.org/wiki/Quaternion */ struct Quaternion { + float w{}; /**< @brief Quaternion entry 0, also denoted as a */ float x{}; /**< @brief Quaternion entry 1, also denoted as b */ float y{}; /**< @brief Quaternion entry 2, also denoted as c */ @@ -172,6 +190,9 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::Quaternion const& quaternion); + + + /** * @brief Euler angle type. * @@ -181,6 +202,7 @@ class Camera : public PluginBase { * For more info see https://en.wikipedia.org/wiki/Euler_angles */ struct EulerAngle { + float roll_deg{}; /**< @brief Roll angle in degrees, positive is banking to the right */ float pitch_deg{}; /**< @brief Pitch angle in degrees, positive is pitching nose up */ float yaw_deg{}; /**< @brief Yaw angle in degrees, positive is clock-wise seen from above */ @@ -200,15 +222,17 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::EulerAngle const& euler_angle); + + + /** * @brief Information about a picture just captured. */ struct CaptureInfo { + Position position{}; /**< @brief Location where the picture was taken */ - Quaternion attitude_quaternion{}; /**< @brief Attitude of the camera when the picture was - taken (quaternion) */ - EulerAngle attitude_euler_angle{}; /**< @brief Attitude of the camera when the picture was - taken (euler angle) */ + Quaternion attitude_quaternion{}; /**< @brief Attitude of the camera when the picture was taken (quaternion) */ + EulerAngle attitude_euler_angle{}; /**< @brief Attitude of the camera when the picture was taken (euler angle) */ uint64_t time_utc_us{}; /**< @brief Timestamp in UTC (since UNIX epoch) in microseconds */ bool is_success{}; /**< @brief True if the capture was successful */ int32_t index{}; /**< @brief Zero-based index of this image since vehicle was armed */ @@ -229,10 +253,14 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::CaptureInfo const& capture_info); + + + /** * @brief Type for video stream settings. */ struct VideoStreamSettings { + float frame_rate_hz{}; /**< @brief Frames per second */ uint32_t horizontal_resolution_pix{}; /**< @brief Horizontal resolution (in pixels) */ uint32_t vertical_resolution_pix{}; /**< @brief Vertical resolution (in pixels) */ @@ -247,56 +275,56 @@ class Camera : public PluginBase { * * @return `true` if items are equal. */ - friend bool - operator==(const Camera::VideoStreamSettings& lhs, const Camera::VideoStreamSettings& rhs); + friend bool operator==(const Camera::VideoStreamSettings& lhs, const Camera::VideoStreamSettings& rhs); /** * @brief Stream operator to print information about a `Camera::VideoStreamSettings`. * * @return A reference to the stream. */ - friend std::ostream& - operator<<(std::ostream& str, Camera::VideoStreamSettings const& video_stream_settings); + friend std::ostream& operator<<(std::ostream& str, Camera::VideoStreamSettings const& video_stream_settings); + + + + + /** * @brief Information about the video stream. */ struct VideoStreamInfo { + /** - * @brief Video stream status type. - */ - enum class VideoStreamStatus { - NotRunning, /**< @brief Video stream is not running. */ - InProgress, /**< @brief Video stream is running. */ - }; - - /** - * @brief Stream operator to print information about a `Camera::VideoStreamStatus`. - * - * @return A reference to the stream. - */ - friend std::ostream& operator<<( - std::ostream& str, - Camera::VideoStreamInfo::VideoStreamStatus const& video_stream_status); - - /** - * @brief Video stream light spectrum type - */ - enum class VideoStreamSpectrum { - Unknown, /**< @brief Unknown. */ - VisibleLight, /**< @brief Visible light. */ - Infrared, /**< @brief Infrared. */ - }; + * @brief Video stream status type. + */ + enum class VideoStreamStatus { + NotRunning, /**< @brief Video stream is not running. */ + InProgress, /**< @brief Video stream is running. */ + }; + /** + * @brief Stream operator to print information about a `Camera::VideoStreamStatus`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo::VideoStreamStatus const& video_stream_status); + /** - * @brief Stream operator to print information about a `Camera::VideoStreamSpectrum`. - * - * @return A reference to the stream. - */ - friend std::ostream& operator<<( - std::ostream& str, - Camera::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum); + * @brief Video stream light spectrum type + */ + enum class VideoStreamSpectrum { + Unknown, /**< @brief Unknown. */ + VisibleLight, /**< @brief Visible light. */ + Infrared, /**< @brief Infrared. */ + }; + /** + * @brief Stream operator to print information about a `Camera::VideoStreamSpectrum`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo::VideoStreamSpectrum const& video_stream_spectrum); + VideoStreamSettings settings{}; /**< @brief Video stream settings */ VideoStreamStatus status{}; /**< @brief Current status of video streaming */ VideoStreamSpectrum spectrum{}; /**< @brief Light-spectrum of the video stream */ @@ -314,59 +342,60 @@ class Camera : public PluginBase { * * @return A reference to the stream. */ - friend std::ostream& - operator<<(std::ostream& str, Camera::VideoStreamInfo const& video_stream_info); + friend std::ostream& operator<<(std::ostream& str, Camera::VideoStreamInfo const& video_stream_info); + + + + + /** * @brief Information about the camera status. */ struct Status { + /** - * @brief Storage status type. - */ - enum class StorageStatus { - NotAvailable, /**< @brief Status not available. */ - Unformatted, /**< @brief Storage is not formatted (i.e. has no recognized file system). - */ - Formatted, /**< @brief Storage is formatted (i.e. has recognized a file system). */ - NotSupported, /**< @brief Storage status is not supported. */ - }; - - /** - * @brief Stream operator to print information about a `Camera::StorageStatus`. - * - * @return A reference to the stream. - */ - friend std::ostream& - operator<<(std::ostream& str, Camera::Status::StorageStatus const& storage_status); - - /** - * @brief Storage type. - */ - enum class StorageType { - Unknown, /**< @brief Storage type unknown. */ - UsbStick, /**< @brief Storage type USB stick. */ - Sd, /**< @brief Storage type SD card. */ - Microsd, /**< @brief Storage type MicroSD card. */ - Hd, /**< @brief Storage type HD mass storage. */ - Other, /**< @brief Storage type other, not listed. */ - }; + * @brief Storage status type. + */ + enum class StorageStatus { + NotAvailable, /**< @brief Status not available. */ + Unformatted, /**< @brief Storage is not formatted (i.e. has no recognized file system). */ + Formatted, /**< @brief Storage is formatted (i.e. has recognized a file system). */ + NotSupported, /**< @brief Storage status is not supported. */ + }; + /** + * @brief Stream operator to print information about a `Camera::StorageStatus`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Camera::Status::StorageStatus const& storage_status); + /** - * @brief Stream operator to print information about a `Camera::StorageType`. - * - * @return A reference to the stream. - */ - friend std::ostream& - operator<<(std::ostream& str, Camera::Status::StorageType const& storage_type); + * @brief Storage type. + */ + enum class StorageType { + Unknown, /**< @brief Storage type unknown. */ + UsbStick, /**< @brief Storage type USB stick. */ + Sd, /**< @brief Storage type SD card. */ + Microsd, /**< @brief Storage type MicroSD card. */ + Hd, /**< @brief Storage type HD mass storage. */ + Other, /**< @brief Storage type other, not listed. */ + }; + /** + * @brief Stream operator to print information about a `Camera::StorageType`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Camera::Status::StorageType const& storage_type); + bool video_on{}; /**< @brief Whether video recording is currently in process */ bool photo_interval_on{}; /**< @brief Whether a photo interval is currently in process */ float used_storage_mib{}; /**< @brief Used storage (in MiB) */ float available_storage_mib{}; /**< @brief Available storage (in MiB) */ float total_storage_mib{}; /**< @brief Total storage (in MiB) */ - float recording_time_s{}; /**< @brief Elapsed time since starting the video recording (in - seconds) */ + float recording_time_s{}; /**< @brief Elapsed time since starting the video recording (in seconds) */ std::string media_folder_name{}; /**< @brief Current folder name where media are saved */ StorageStatus storage_status{}; /**< @brief Storage status */ uint32_t storage_id{}; /**< @brief Storage ID starting at 1 */ @@ -387,10 +416,14 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::Status const& status); + + + /** * @brief Type to represent a setting option. */ struct Option { + std::string option_id{}; /**< @brief Name of the option (machine readable) */ std::string option_description{}; /**< @brief Description of the option (human readable) */ }; @@ -409,17 +442,18 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::Option const& option); + + + /** * @brief Type to represent a setting with a selected option. */ struct Setting { + std::string setting_id{}; /**< @brief Name of a setting (machine readable) */ - std::string setting_description{}; /**< @brief Description of the setting (human readable). - This field is meant to be read from the drone, ignore - it when setting. */ + std::string setting_description{}; /**< @brief Description of the setting (human readable). This field is meant to be read from the drone, ignore it when setting. */ Option option{}; /**< @brief Selected option */ - bool is_range{}; /**< @brief If option is given as a range. This field is meant to be read - from the drone, ignore it when setting. */ + bool is_range{}; /**< @brief If option is given as a range. This field is meant to be read from the drone, ignore it when setting. */ }; /** @@ -436,15 +470,17 @@ class Camera : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Camera::Setting const& setting); + + + /** * @brief Type to represent a setting with a list of options to choose from. */ struct SettingOptions { + std::string setting_id{}; /**< @brief Name of the setting (machine readable) */ - std::string - setting_description{}; /**< @brief Description of the setting (human readable) */ - std::vector