Skip to content

Commit

Permalink
gimbal: added doxygen strings
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Oct 26, 2017
1 parent 980b88d commit 97d98b9
Showing 1 changed file with 60 additions and 6 deletions.
66 changes: 60 additions & 6 deletions plugins/gimbal/gimbal.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,33 +6,87 @@ namespace dronecore {

class GimbalImpl;

/**
* @brief The Gimbal class enables to control a gimbal.
*
* Synchronous and asynchronous variants of the gimbal methods are supplied.
*/
class Gimbal
{
public:
/**
* @brief Constructor (internal use only).
*
* @param impl Private internal implementation.
*/
explicit Gimbal(GimbalImpl *impl);

/**
* @brief Destructor (internal use only).
*/
~Gimbal();

/**
* @brief Possible results returned for gimbal commands.
*/
enum class Result {
SUCCESS = 0,
ERROR,
TIMEOUT,
UNKNOWN
SUCCESS = 0, /**< @brief Success. The gimbal command was accepted. */
ERROR, /**< @brief Error. An error occured sending the command. */
TIMEOUT, /**< @brief Timeout. A timeout occured sending the command. */
UNKNOWN /**< @brief Unspecified error. */
};

/**
* @brief Returns a human-readable English string for Gimbal::Result.
*
* @param Result The enum value for which a human readable string is required.
* @return Human readable string for the Gimbal::Result.
*/
static const char *result_str(Result result);

/**
* @brief Callback type for asynchronous Gimbal calls.
*/
typedef std::function<void(Result)> result_callback_t;

/**
* @brief Set gimbal pitch and yaw angles (synchronous).
*
* This sets the desired pitch and yaw angles of a gimbal.
* The function will return when the command is accepted, however, it might
* take the gimbal longer to actually be set to the new angles.
*
* @param pitch_deg The pitch angle in degrees. Negative to point down.
* @param yaw_deg The yaw angle in degrees. Positive for clock-wise, range -180..180 or 0..360.
* @return Result of request.
*/
Result set_pitch_and_yaw(float pitch_deg, float yaw_deg);

/**
* @brief Set gimbal pitch and yaw angles (asynchronous).
*
* This sets the desired pitch and yaw angles of a gimbal.
* The callback will be called when the command is accepted, however, it might
* take the gimbal longer to actually be set to the new angles.
*
* @param pitch_deg The pitch angle in degrees. Negative to point down.
* @param yaw_deg The yaw angle in degrees. Positive for clock-wise, range -180..180 or 0..360.
* @param callback Function to call with result of request.
*/
void set_pitch_and_yaw_async(float pitch_deg, float yaw_deg, result_callback_t callback);

// Non-copyable
/**
* @brief Copy constructor (object is not copyable).
*/
Gimbal(const Gimbal &) = delete;

/**
* @brief Equality operator (object is not copyable).
*/
const Gimbal &operator=(const Gimbal &) = delete;

private:
// Underlying implementation, set at instantiation
/** @private Underlying implementation, set at instantiation */
GimbalImpl *_impl;
};

Expand Down

0 comments on commit 97d98b9

Please sign in to comment.