Skip to content
Snippets Groups Projects
Commit dd7e8238 authored by Daniel Agar's avatar Daniel Agar
Browse files

delete examples mc_pos_control_multiplatform

parent 53e6d7eb
No related branches found
No related tags found
No related merge requests found
############################################################################
#
# Copyright (c) 2015 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 examples__mc_pos_control_multiplatform
MAIN mc_pos_control_m
SRCS
mc_pos_control_main.cpp
mc_pos_control_start_nuttx.cpp
mc_pos_control.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
This diff is collapsed.
/****************************************************************************
*
* Copyright (c) 2013 - 2015 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 mc_pos_control.h
* Multicopter position controller.
*
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#pragma once
#include <px4.h>
#include <cstdio>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <math.h>
// #include <poll.h>
// #include <drivers/drv_hrt.h>
// #include <arch/board/board.h>
// #include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
#include <lib/geo/geo.h>
// #include <mavlink/mavlink_log.h>
using namespace px4;
class MulticopterPositionControlMultiplatform
{
public:
/**
* Constructor
*/
MulticopterPositionControlMultiplatform();
/**
* Destructor, also kills task.
*/
~MulticopterPositionControlMultiplatform();
/* Callbacks for topics */
void handle_vehicle_attitude(const px4_vehicle_attitude &msg);
void handle_parameter_update(const px4_parameter_update &msg);
void handle_position_setpoint_triplet(const px4_position_setpoint_triplet &msg);
void spin() { _n.spin(); }
protected:
const float alt_ctl_dz = 0.2f;
bool _task_should_exit; /**< if true, task should exit */
int _control_task; /**< task handle for task */
//orb_advert_t _mavlink_log_pub; /**< mavlink log advert */
Publisher<px4_vehicle_attitude_setpoint> *_att_sp_pub; /**< attitude setpoint publication */
Publisher<px4_vehicle_local_position_setpoint> *_local_pos_sp_pub; /**< vehicle local position setpoint publication */
Subscriber<px4_vehicle_attitude> *_att; /**< vehicle attitude */
Subscriber<px4_vehicle_control_mode> *_control_mode; /**< vehicle control mode */
Subscriber<px4_parameter_update> *_parameter_update; /**< parameter update */
Subscriber<px4_manual_control_setpoint> *_manual_control_sp; /**< manual control setpoint */
Subscriber<px4_actuator_armed> *_armed; /**< actuator arming status */
Subscriber<px4_vehicle_local_position> *_local_pos; /**< local position */
Subscriber<px4_position_setpoint_triplet> *_pos_sp_triplet; /**< local position */
Subscriber<px4_vehicle_local_position_setpoint> *_local_pos_sp; /**< local position */
px4_vehicle_attitude_setpoint _att_sp_msg;
px4_vehicle_local_position_setpoint _local_pos_sp_msg;
px4::NodeHandle _n;
px4::AppState _appState;
struct {
px4::ParameterFloat thr_min;
px4::ParameterFloat thr_max;
px4::ParameterFloat z_p;
px4::ParameterFloat z_vel_p;
px4::ParameterFloat z_vel_i;
px4::ParameterFloat z_vel_d;
px4::ParameterFloat z_vel_max;
px4::ParameterFloat z_ff;
px4::ParameterFloat xy_p;
px4::ParameterFloat xy_vel_p;
px4::ParameterFloat xy_vel_i;
px4::ParameterFloat xy_vel_d;
px4::ParameterFloat xy_vel_max;
px4::ParameterFloat xy_ff;
px4::ParameterFloat tilt_max_air;
px4::ParameterFloat land_speed;
px4::ParameterFloat tilt_max_land;
px4::ParameterFloat man_roll_max;
px4::ParameterFloat man_pitch_max;
px4::ParameterFloat man_yaw_max;
px4::ParameterFloat mc_att_yaw_p; // needed for calculating reasonable attitude setpoints in manual
} _params_handles; /**< handles for interesting parameters */
struct {
float thr_min;
float thr_max;
float tilt_max_air;
float land_speed;
float tilt_max_land;
float man_roll_max;
float man_pitch_max;
float man_yaw_max;
float mc_att_yaw_p;
math::Vector<3> pos_p;
math::Vector<3> vel_p;
math::Vector<3> vel_i;
math::Vector<3> vel_d;
math::Vector<3> vel_ff;
math::Vector<3> vel_max;
math::Vector<3> sp_offs_max;
} _params;
struct map_projection_reference_s _ref_pos;
float _ref_alt;
uint64_t _ref_timestamp;
bool _reset_pos_sp;
bool _reset_alt_sp;
bool _mode_auto;
math::Vector<3> _pos;
math::Vector<3> _pos_sp;
math::Vector<3> _vel;
math::Vector<3> _vel_sp;
math::Vector<3> _vel_prev; /**< velocity on previous step */
math::Vector<3> _vel_ff;
math::Vector<3> _sp_move_rate;
math::Vector<3> _thrust_int;
math::Matrix<3, 3> _R;
/**
* Update our local parameter cache.
*/
int parameters_update();
/**
* Update control outputs
*/
void control_update();
static float scale_control(float ctl, float end, float dz);
/**
* Update reference for local position projection
*/
void update_ref();
/**
* Reset position setpoint to current position
*/
void reset_pos_sp();
/**
* Reset altitude setpoint to current altitude
*/
void reset_alt_sp();
/**
* Check if position setpoint is too far from current position and adjust it if needed.
*/
void limit_pos_sp_offset();
/**
* Set position setpoint using manual control
*/
void control_manual(float dt);
/**
* Set position setpoint using offboard control
*/
void control_offboard(float dt);
bool cross_sphere_line(const math::Vector<3> &sphere_c, const float sphere_r,
const math::Vector<3> &line_a, const math::Vector<3> &line_b, math::Vector<3> &res);
/**
* Set position setpoint for AUTO
*/
void control_auto(float dt);
/**
* Select between barometric and global (AMSL) altitudes
*/
void select_alt(bool global);
};
/****************************************************************************
*
* Copyright (c) 2013 - 2015 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 mc_pos_control_main.cpp
* Multicopter position controller.
*
* The controller has two loops: P loop for position error and PID loop for velocity error.
* Output of velocity controller is thrust vector that splitted to thrust direction
* (i.e. rotation matrix for multicopter orientation) and thrust module (i.e. multicopter thrust itself).
* Controller doesn't use Euler angles for work, they generated only for more human-friendly control and logging.
*
* @author Anton Babushkin <anton.babushkin@me.com>
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include "mc_pos_control.h"
bool mc_pos_control_thread_running = false; /**< Deamon status flag */
#if defined(__PX4_ROS)
int main(int argc, char **argv)
#else
int mc_pos_control_start_main(int argc, char **argv); // Prototype for missing declearation error with nuttx
int mc_pos_control_start_main(int argc, char **argv)
#endif
{
px4::init(argc, argv, "mc_pos_control_m");
PX4_INFO("starting");
MulticopterPositionControlMultiplatform posctl;
mc_pos_control_thread_running = true;
posctl.spin();
PX4_INFO("exiting.");
mc_pos_control_thread_running = false;
return 0;
}
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Anton Babushkin <anton.babushkin@me.com>
*
* 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) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file mc_pos_control_params.c
* Multicopter position controller parameters.
*
* @author Anton Babushkin <anton.babushkin@me.com>
*/
/**
* Minimum thrust
*
* Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust.
*
* @min 0.0
* @max 1.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_THR_MIN);
/**
* Maximum thrust
*
* Limit max allowed thrust.
*
* @min 0.0
* @max 1.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_THR_MAX);
/**
* Proportional gain for vertical position error
*
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_Z_P);
/**
* Proportional gain for vertical velocity error
*
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_Z_VEL_P);
/**
* Integral gain for vertical velocity error
*
* Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.
*
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_Z_VEL_I);
/**
* Differential gain for vertical velocity error
*
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_Z_VEL_D);
/**
* Maximum vertical velocity
*
* Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL).
*
* @unit m/s
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_Z_VEL_MAX);
/**
* Vertical velocity feed forward
*
* Feed forward weight for altitude control in stabilized modes (ALTCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
*
* @min 0.0
* @max 1.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_Z_FF);
/**
* Proportional gain for horizontal position error
*
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_XY_P);
/**
* Proportional gain for horizontal velocity error
*
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_XY_VEL_P);
/**
* Integral gain for horizontal velocity error
*
* Non-zero value allows to resist wind.
*
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_XY_VEL_I);
/**
* Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
*
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_XY_VEL_D);
/**
* Maximum horizontal velocity
*
* Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).
*
* @unit m/s
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_XY_VEL_MAX);
/**
* Horizontal velocity feed forward
*
* Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
*
* @min 0.0
* @max 1.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_XY_FF);
/**
* Maximum tilt angle in air
*
* Limits maximum tilt in AUTO and POSCTRL modes during flight.
*
* @unit deg
* @min 0.0
* @max 90.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_TILTMAX_AIR);
/**
* Maximum tilt during landing
*
* Limits maximum tilt angle on landing.
*
* @unit deg
* @min 0.0
* @max 90.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_TILTMAX_LND);
/**
* Landing descend rate
*
* @unit m/s
* @min 0.0
* @group Multicopter Position Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_LAND_SPEED);
/**
* Max manual roll
*
* @unit deg
* @min 0.0
* @max 90.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_MAN_R_MAX);
/**
* Max manual pitch
*
* @unit deg
* @min 0.0
* @max 90.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_MAN_P_MAX);
/**
* Max manual yaw rate
*
* @unit deg/s
* @min 0.0
* @group Multicopter Attitude Control
*/
PX4_PARAM_DEFINE_FLOAT(MPP_MAN_Y_MAX);
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
* Author: @author Anton Babushkin <anton.babushkin@me.com>
*
* 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 mc_pos_control_params.h
* Multicopter position controller parameters.
*
* @author Anton Babushkin <anton.babushkin@me.com>
*/
#pragma once
#define PARAM_MPP_THR_MIN_DEFAULT 0.1f
#define PARAM_MPP_THR_MAX_DEFAULT 1.0f
#define PARAM_MPP_Z_P_DEFAULT 1.0f
#define PARAM_MPP_Z_VEL_P_DEFAULT 0.1f
#define PARAM_MPP_Z_VEL_I_DEFAULT 0.02f
#define PARAM_MPP_Z_VEL_D_DEFAULT 0.0f
#define PARAM_MPP_Z_VEL_MAX_DEFAULT 5.0f
#define PARAM_MPP_Z_FF_DEFAULT 0.5f
#define PARAM_MPP_XY_P_DEFAULT 1.0f
#define PARAM_MPP_XY_VEL_P_DEFAULT 0.1f
#define PARAM_MPP_XY_VEL_I_DEFAULT 0.02f
#define PARAM_MPP_XY_VEL_D_DEFAULT 0.01f
#define PARAM_MPP_XY_VEL_MAX_DEFAULT 5.0f
#define PARAM_MPP_XY_FF_DEFAULT 0.5f
#define PARAM_MPP_TILTMAX_AIR_DEFAULT 45.0f
#define PARAM_MPP_TILTMAX_LND_DEFAULT 15.0f
#define PARAM_MPP_LAND_SPEED_DEFAULT 1.0f
#define PARAM_MPP_MAN_R_MAX_DEFAULT 35.0f
#define PARAM_MPP_MAN_P_MAX_DEFAULT 35.0f
#define PARAM_MPP_MAN_Y_MAX_DEFAULT 120.0f
/****************************************************************************
*
* Copyright (C) 2013 - 2015 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 mc_pos_control_m_start_nuttx.cpp
*
* @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include <px4_tasks.h>
#include <string.h>
#include <cstdlib>
#include <systemlib/err.h>
extern bool mc_pos_control_thread_running;
int mc_pos_control_daemon_task; /**< Handle of deamon task / thread */
namespace px4
{
bool mc_pos_control_task_should_exit = false;
}
using namespace px4;
extern int mc_pos_control_start_main(int argc, char **argv);
extern "C" __EXPORT int mc_pos_control_m_main(int argc, char *argv[]);
int mc_pos_control_m_main(int argc, char *argv[])
{
if (argc < 2) {
PX4_WARN("usage: mc_pos_control_m {start|stop|status}");
}
if (!strcmp(argv[1], "start")) {
if (mc_pos_control_thread_running) {
warnx("already running");
/* this is not an error */
return 0;
}
mc_pos_control_task_should_exit = false;
mc_pos_control_daemon_task = px4_task_spawn_cmd("mc_pos_control_m",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
2500,
mc_pos_control_start_main,
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
return 0;
}
if (!strcmp(argv[1], "stop")) {
mc_pos_control_task_should_exit = true;
return 0;
}
if (!strcmp(argv[1], "status")) {
if (mc_pos_control_thread_running) {
warnx("is running");
} else {
warnx("not started");
}
return 0;
}
warnx("unrecognized command");
return 1;
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment