forked from Archive/PX4-Autopilot
navigator: Adjust to uORB mission changes
This commit is contained in:
parent
d8690d7de3
commit
51293ad554
|
@ -45,6 +45,7 @@
|
|||
#include <mavlink/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
#include <navigator/navigation.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
|
|
|
@ -44,6 +44,7 @@
|
|||
#include <mavlink/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
#include <navigator/navigation.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
#include <mavlink/mavlink_log.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
#include <navigator/navigation.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
|
|
|
@ -55,6 +55,7 @@
|
|||
#include <systemlib/err.h>
|
||||
#include <geo/geo.h>
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
#include <navigator/navigation.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
|
|
|
@ -43,6 +43,8 @@
|
|||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <navigator/navigation.h>
|
||||
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
|
|
|
@ -32,19 +32,18 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file mission.h
|
||||
* @file navigation.h
|
||||
* Definition of a mission consisting of mission items.
|
||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||
* @author Julian Oes <joes@student.ethz.ch>
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#ifndef TOPIC_MISSION_H_
|
||||
#define TOPIC_MISSION_H_
|
||||
#ifndef NAVIGATION_H_
|
||||
#define NAVIGATION_H_
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
#define NUM_MISSIONS_SUPPORTED 256
|
||||
|
||||
|
@ -103,15 +102,7 @@ struct mission_item_s {
|
|||
int actuator_value; /**< new value for selected actuator in ms 900...2000 */
|
||||
};
|
||||
|
||||
/**
|
||||
* This topic used to notify navigator about mission changes, mission itself and new mission state
|
||||
* must be stored in dataman before publication.
|
||||
*/
|
||||
struct mission_s {
|
||||
int dataman_id; /**< default 0, there are two offboard storage places in the dataman: 0 or 1 */
|
||||
unsigned count; /**< count of the missions stored in the dataman */
|
||||
int current_seq; /**< default -1, start at the one changed latest */
|
||||
};
|
||||
#include <uORB/topics/mission.h>
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
#include <navigator/navigation.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
#include <geo/geo.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <navigator/navigation.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
|
||||
#include "navigator.h"
|
||||
|
|
|
@ -47,7 +47,7 @@
|
|||
#include <geo/geo.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <navigator/navigation.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
|
||||
#include "navigator.h"
|
||||
|
|
|
@ -44,8 +44,7 @@
|
|||
#include <controllib/blocks.hpp>
|
||||
#include <controllib/block/BlockParam.hpp>
|
||||
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <uORB/topics/mission.h>
|
||||
#include <navigator/navigation.h>
|
||||
#include <uORB/topics/home_position.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
|
||||
|
|
Loading…
Reference in New Issue