Browse Source

FlightTasks: introduce new library to handle advanced features like orbit follow me and so on

it's only a draft setup yet and not functional for real use

the object is for now managed by the mc_pos_control module
but it stays as encapsulated as possible to enable the instance to reside in any trajectory module in the future
sbg
Matthias Grob 8 years ago committed by Beat Küng
parent
commit
93ae260f44
  1. 42
      src/lib/FlightTasks/CMakeLists.txt
  2. 70
      src/lib/FlightTasks/FlightTasks.hpp
  3. 88
      src/lib/FlightTasks/tasks/FlightTask.hpp
  4. 75
      src/lib/FlightTasks/tasks/FlightTaskOrbit.hpp

42
src/lib/FlightTasks/CMakeLists.txt

@ -0,0 +1,42 @@ @@ -0,0 +1,42 @@
############################################################################
#
# Copyright (c) 2017 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE lib__flight_tasks
SRCS
FlightTask.h
tasks/FlightTaskOrbit.cpp
DEPENDS
platforms__common
modules__uORB
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :

70
src/lib/FlightTasks/FlightTasks.hpp

@ -0,0 +1,70 @@ @@ -0,0 +1,70 @@
/****************************************************************************
*
* Copyright (c) 2017 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file flight_taks.h
*
* Library class to hold and manage all implemented flight task instances
*
* @author Matthias Grob <maetugr@gmail.com>
*/
#pragma once
#include "tasks/FlightTask.hpp"
#include "tasks/FlightTaskOrbit.hpp"
class FlightTasks
{
public:
FlightTasks() {};
~FlightTasks() {};
/**
* Call regularly in the control loop cycle to execute the task
* @param TODO
* @return 0 on success, >0 on error otherwise
*/
int update(manual_control_setpoint_s *manual_control_setpoint, vehicle_local_position_s *vehicle_local_position) { return 0; };
/**
* Call to get result of the task execution
* @return pointer to
*/
const vehicle_local_position_setpoint_s *get_local_position_setpoint() const { return Orbit.get_local_position_setpoint(); };
private:
FlightTaskOrbit Orbit;
};

88
src/lib/FlightTasks/tasks/FlightTask.hpp

@ -0,0 +1,88 @@ @@ -0,0 +1,88 @@
/****************************************************************************
*
* Copyright (c) 2017 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file FlightTask.h
*
* Abstract base class for different advanced flight tasks like orbit, follow me, ...
*
* @author Matthias Grob <maetugr@gmail.com>
*/
#pragma once
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
class FlightTask
{
public:
FlightTask()
{
vehicle_local_position_setpoint.x = 1;
vehicle_local_position_setpoint.y = 2;
vehicle_local_position_setpoint.z = -3;
};
virtual ~FlightTask() {};
/**
* Call once on the event where you switch to the task
* @return 0 on success, >0 on error otherwise
*/
virtual int activate() = 0;
/**
* Call once on the event of switching away from the task
* @return 0 on success, >0 on error otherwise
*/
virtual int disable() = 0;
/**
* Call regularly in the control loop cycle to execute the task
* @param TODO
* @return 0 on success, >0 on error otherwise
*/
virtual int update(manual_control_setpoint_s *manual_control_setpoint,
vehicle_local_position_s *vehicle_local_position) = 0;
/**
* Call to get result of the task execution
* @return pointer to
*/
const vehicle_local_position_setpoint_s *get_local_position_setpoint() const { return &vehicle_local_position_setpoint; };
private:
vehicle_local_position_setpoint_s vehicle_local_position_setpoint;
};

75
src/lib/FlightTasks/tasks/FlightTaskOrbit.hpp

@ -0,0 +1,75 @@ @@ -0,0 +1,75 @@
/****************************************************************************
*
* Copyright (c) 2017 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file FlightTaskOrbit.h
*
* Flight task for orbiting in a circle around a target position
*
* @author Matthias Grob <maetugr@gmail.com>
*/
#pragma once
#include "FlightTask.hpp"
class FlightTaskOrbit : public FlightTask
{
public:
FlightTaskOrbit() {};
virtual ~FlightTaskOrbit() {};
/**
* Call once on the event where you switch to the task
* @return 0 on success, >0 on error otherwise
*/
virtual int activate() { return 0; };
/**
* Call once on the event of switching away from the task
* @return 0 on success, >0 on error otherwise
*/
virtual int disable() { return 0; };
/**
* Call regularly in the control loop cycle to execute the task
* @param TODO
* @return 0 on success, >0 on error otherwise
*/
virtual int update(manual_control_setpoint_s *manual_control_setpoint,
vehicle_local_position_s *vehicle_local_position) { return 0; };
private:
};
Loading…
Cancel
Save