aboutsummaryrefslogtreecommitdiff
path: root/src/modules/controllib/uorb/blocks.hpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/controllib/uorb/blocks.hpp')
-rw-r--r--src/modules/controllib/uorb/blocks.hpp23
1 files changed, 23 insertions, 0 deletions
diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp
index 54f31735c..9c0720aa5 100644
--- a/src/modules/controllib/uorb/blocks.hpp
+++ b/src/modules/controllib/uorb/blocks.hpp
@@ -57,6 +57,10 @@
#include <drivers/drv_hrt.h>
#include <poll.h>
+extern "C" {
+#include <systemlib/geo/geo.h>
+}
+
#include "../blocks.hpp"
#include "UOrbSubscription.hpp"
#include "UOrbPublication.hpp"
@@ -65,6 +69,25 @@ namespace control
{
/**
+ * Waypoint Guidance block
+ */
+class __EXPORT BlockWaypointGuidance : public SuperBlock
+{
+private:
+ BlockLimitSym _xtYawLimit;
+ BlockP _xt2Yaw;
+ float _psiCmd;
+public:
+ BlockWaypointGuidance(SuperBlock *parent, const char *name);
+ virtual ~BlockWaypointGuidance();
+ void update(vehicle_global_position_s &pos,
+ vehicle_attitude_s &att,
+ vehicle_global_position_setpoint_s &posCmd,
+ vehicle_global_position_setpoint_s &lastPosCmd);
+ float getPsiCmd() { return _psiCmd; }
+};
+
+/**
* UorbEnabledAutopilot
*/
class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock