Browse Source

FixedwingPositionControl update copyright and control_task

sbg
Daniel Agar 8 years ago
parent
commit
3313ade291
  1. 2
      src/modules/fw_pos_control_l1/CMakeLists.txt
  2. 23
      src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp
  3. 4
      src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp

2
src/modules/fw_pos_control_l1/CMakeLists.txt

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
# Copyright (c) 2015-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

23
src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp

@ -31,35 +31,14 @@ @@ -31,35 +31,14 @@
*
****************************************************************************/
/**
* @file fw_pos_control_l1_main.c
* Implementation of a generic position controller based on the L1 norm. Outputs a bank / roll
* angle, equivalent to a lateral motion (for copters and rovers).
*
* Original publication for horizontal control class:
* S. Park, J. Deyst, and J. P. How, "A New Nonlinear Guidance Logic for Trajectory Tracking,"
* Proceedings of the AIAA Guidance, Navigation and Control
* Conference, Aug 2004. AIAA-2004-4900.
*
* Original implementation for total energy control class:
* Paul Riseborough and Andrew Tridgell, 2013 (code in lib/external_lgpl)
*
* More details and acknowledgements in the referenced library headers.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@gmail.com>
* @author Andreas Antener <andreas@uaventure.com>
*/
#include "FixedwingPositionControl.hpp"
extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[]);
FixedwingPositionControl *l1_control::g_control;
static int _control_task = -1; ///< task handle for sensor task */
FixedwingPositionControl::FixedwingPositionControl() :
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control"))
{
_parameter_handles.l1_period = param_find("FW_L1_PERIOD");

4
src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp

@ -61,8 +61,6 @@ @@ -61,8 +61,6 @@
#include "Landingslope.hpp"
#include <arch/board/board.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_hrt.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
#include <external_lgpl/tecs/tecs.h>
@ -86,8 +84,6 @@ @@ -86,8 +84,6 @@
#include <uORB/uORB.h>
#include <vtol_att_control/vtol_type.h>
static int _control_task = -1; ///< task handle for sensor task */
#define HDG_HOLD_DIST_NEXT 3000.0f // initial distance of waypoint in front of plane in heading hold mode
#define HDG_HOLD_REACHED_DIST 1000.0f // distance (plane to waypoint in front) at which waypoints are reset in heading hold mode
#define HDG_HOLD_SET_BACK_DIST 100.0f // distance by which previous waypoint is set behind the plane

Loading…
Cancel
Save