mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
delete obsolete segway example
This commit is contained in:
parent
fd67bd0680
commit
0486d69240
@ -79,5 +79,4 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
@ -107,7 +107,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -119,5 +119,4 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
)
|
||||
|
||||
@ -120,5 +120,4 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
@ -112,7 +112,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -112,7 +112,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -76,5 +76,4 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
@ -74,5 +74,4 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
@ -84,5 +84,4 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
@ -82,5 +82,4 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
@ -90,7 +90,6 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
#uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -94,7 +94,6 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
#uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -116,7 +116,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -111,7 +111,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -102,7 +102,6 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
#uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -119,6 +119,5 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
#uuv_example_app
|
||||
)
|
||||
|
||||
@ -113,5 +113,4 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
)
|
||||
|
||||
@ -113,5 +113,4 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
)
|
||||
|
||||
@ -120,7 +120,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -120,7 +120,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -119,7 +119,6 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
#uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -106,7 +106,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -109,7 +109,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -106,7 +106,6 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
#uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -118,7 +118,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -118,7 +118,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -120,7 +120,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -120,7 +120,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -120,7 +120,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -118,6 +118,5 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
)
|
||||
|
||||
@ -119,6 +119,5 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
#uuv_example_app
|
||||
)
|
||||
|
||||
@ -120,6 +120,5 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
uuv_example_app
|
||||
)
|
||||
|
||||
@ -76,5 +76,4 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
@ -75,5 +75,4 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
@ -79,7 +79,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
set(config_sitl_viewer jmavsim CACHE STRING "viewer for sitl")
|
||||
|
||||
@ -80,7 +80,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
set(config_sitl_viewer jmavsim CACHE STRING "viewer for sitl")
|
||||
|
||||
@ -79,7 +79,6 @@ px4_add_board(
|
||||
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
rover_steering_control # Rover example app
|
||||
segway
|
||||
)
|
||||
|
||||
set(config_sitl_viewer jmavsim CACHE STRING "viewer for sitl")
|
||||
|
||||
@ -113,7 +113,6 @@ px4_add_board(
|
||||
#px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
|
||||
#px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
|
||||
#rover_steering_control # Rover example app
|
||||
#segway
|
||||
#uuv_example_app
|
||||
|
||||
)
|
||||
|
||||
@ -1,66 +0,0 @@
|
||||
#include "BlockSegwayController.hpp"
|
||||
|
||||
using matrix::Eulerf;
|
||||
using matrix::Quatf;
|
||||
|
||||
void BlockSegwayController::update()
|
||||
{
|
||||
// wait for a sensor update, check for exit condition every 100 ms
|
||||
if (px4_poll(&_attPoll, 1, 100) < 0) { return; } // poll error
|
||||
|
||||
uint64_t newTimeStamp = hrt_absolute_time();
|
||||
float dt = (newTimeStamp - _timeStamp) / 1.0e6f;
|
||||
_timeStamp = newTimeStamp;
|
||||
|
||||
// check for sane values of dt
|
||||
// to prevent large control responses
|
||||
if (dt > 1.0f || dt < 0) { return; }
|
||||
|
||||
// set dt for all child blocks
|
||||
setDt(dt);
|
||||
|
||||
// check for new updates
|
||||
if (_param_update.updated()) { updateParams(); }
|
||||
|
||||
// get new information from subscriptions
|
||||
updateSubscriptions();
|
||||
|
||||
actuator_controls_s &actuators = _actuators.get();
|
||||
|
||||
// default all output to zero unless handled by mode
|
||||
for (unsigned i = 2; i < actuator_controls_s::NUM_ACTUATOR_CONTROLS; i++) {
|
||||
actuators.control[i] = 0.0f;
|
||||
}
|
||||
|
||||
const uint8_t &nav_state = _status.get().nav_state;
|
||||
|
||||
// only update guidance in auto mode
|
||||
if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION) {
|
||||
// update guidance
|
||||
}
|
||||
|
||||
Eulerf euler = Eulerf(Quatf(_att.get().q));
|
||||
|
||||
// compute speed command
|
||||
float spdCmd = -th2v.update(euler.theta()) - q2v.update(_angular_velocity.get().xyz[1]);
|
||||
|
||||
// handle autopilot modes
|
||||
if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION ||
|
||||
nav_state == vehicle_status_s::NAVIGATION_STATE_ALTCTL ||
|
||||
nav_state == vehicle_status_s::NAVIGATION_STATE_POSCTL) {
|
||||
|
||||
actuators.control[0] = spdCmd;
|
||||
actuators.control[1] = spdCmd;
|
||||
|
||||
} else if (nav_state == vehicle_status_s::NAVIGATION_STATE_STAB) {
|
||||
actuators.control[0] = spdCmd;
|
||||
actuators.control[1] = spdCmd;
|
||||
|
||||
} else if (nav_state == vehicle_status_s::NAVIGATION_STATE_MANUAL) {
|
||||
actuators.control[CH_LEFT] = _manual.get().z;
|
||||
actuators.control[CH_RIGHT] = -_manual.get().x;
|
||||
}
|
||||
|
||||
// publish
|
||||
_actuators.update();
|
||||
}
|
||||
@ -1,34 +0,0 @@
|
||||
#pragma once
|
||||
|
||||
#include <px4_posix.h>
|
||||
#include <controllib/blocks.hpp>
|
||||
#include "blocks.hpp"
|
||||
|
||||
using control::BlockPI;
|
||||
using control::BlockP;
|
||||
|
||||
class BlockSegwayController : public control::BlockUorbEnabledAutopilot
|
||||
{
|
||||
public:
|
||||
BlockSegwayController() :
|
||||
BlockUorbEnabledAutopilot(nullptr, "SEG"),
|
||||
th2v(this, "TH2V"),
|
||||
q2v(this, "Q2V"),
|
||||
_attPoll(),
|
||||
_timeStamp(0)
|
||||
{
|
||||
_attPoll.fd = _att.getHandle();
|
||||
_attPoll.events = POLLIN;
|
||||
}
|
||||
|
||||
void update();
|
||||
|
||||
private:
|
||||
enum {CH_LEFT, CH_RIGHT};
|
||||
|
||||
BlockPI th2v;
|
||||
BlockP q2v;
|
||||
|
||||
px4_pollfd_struct_t _attPoll;
|
||||
uint64_t _timeStamp;
|
||||
};
|
||||
@ -1,42 +0,0 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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__segway
|
||||
MAIN segway
|
||||
SRCS
|
||||
blocks.cpp
|
||||
segway_main.cpp
|
||||
BlockSegwayController.cpp
|
||||
DEPENDS
|
||||
)
|
||||
|
||||
@ -1,104 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 uorb_blocks.cpp
|
||||
*
|
||||
* uorb block library code
|
||||
*/
|
||||
|
||||
#include "blocks.hpp"
|
||||
#include <lib/ecl/geo/geo.h>
|
||||
#include <matrix/math.hpp>
|
||||
|
||||
using matrix::wrap_2pi;
|
||||
|
||||
namespace control
|
||||
{
|
||||
|
||||
BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) :
|
||||
SuperBlock(parent, name),
|
||||
_xtYawLimit(this, "XT2YAW"),
|
||||
_xt2Yaw(this, "XT2YAW"),
|
||||
_psiCmd(0)
|
||||
{
|
||||
}
|
||||
|
||||
void BlockWaypointGuidance::update(
|
||||
const vehicle_global_position_s &pos,
|
||||
const vehicle_attitude_s &att,
|
||||
const position_setpoint_s &missionCmd,
|
||||
const position_setpoint_s &lastMissionCmd)
|
||||
{
|
||||
|
||||
// heading to waypoint
|
||||
float psiTrack = get_bearing_to_next_waypoint(
|
||||
(double)pos.lat / (double)1e7,
|
||||
(double)pos.lon / (double)1e7,
|
||||
missionCmd.lat,
|
||||
missionCmd.lon);
|
||||
|
||||
// cross track
|
||||
struct crosstrack_error_s xtrackError;
|
||||
get_distance_to_line(&xtrackError,
|
||||
(double)pos.lat / (double)1e7,
|
||||
(double)pos.lon / (double)1e7,
|
||||
lastMissionCmd.lat,
|
||||
lastMissionCmd.lon,
|
||||
missionCmd.lat,
|
||||
missionCmd.lon);
|
||||
|
||||
_psiCmd = wrap_2pi(psiTrack -
|
||||
_xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
|
||||
}
|
||||
|
||||
BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) :
|
||||
SuperBlock(parent, name),
|
||||
// subscriptions
|
||||
_manual(ORB_ID(manual_control_setpoint), 20, 0, &getSubscriptions()),
|
||||
_param_update(ORB_ID(parameter_update), 1000, 0, &getSubscriptions()), // limit to 1 Hz
|
||||
_missionCmd(ORB_ID(position_setpoint_triplet), 20, 0, &getSubscriptions()),
|
||||
_att(ORB_ID(vehicle_attitude), 20, 0, &getSubscriptions()),
|
||||
_angular_velocity(ORB_ID(vehicle_angular_velocity), 20, 0, &getSubscriptions()),
|
||||
_attCmd(ORB_ID(vehicle_attitude_setpoint), 20, 0, &getSubscriptions()),
|
||||
_pos(ORB_ID(vehicle_global_position), 20, 0, &getSubscriptions()),
|
||||
_ratesCmd(ORB_ID(vehicle_rates_setpoint), 20, 0, &getSubscriptions()),
|
||||
_status(ORB_ID(vehicle_status), 20, 0, &getSubscriptions()),
|
||||
|
||||
// publications
|
||||
_actuators(ORB_ID(actuator_controls_0))
|
||||
{
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@ -1,115 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 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 uorb_blocks.h
|
||||
*
|
||||
* uorb block library code
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <math.h>
|
||||
#include <poll.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <controllib/blocks.hpp>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <uORB/SubscriptionPollable.hpp>
|
||||
#include <uORB/topics/manual_control_setpoint.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/vehicle_angular_velocity.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
|
||||
#include <uORB/Publication.hpp>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
|
||||
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() = default;
|
||||
|
||||
void update(const vehicle_global_position_s &pos,
|
||||
const vehicle_attitude_s &att,
|
||||
const position_setpoint_s &missionCmd,
|
||||
const position_setpoint_s &lastMissionCmd);
|
||||
|
||||
float getPsiCmd() { return _psiCmd; }
|
||||
};
|
||||
|
||||
/**
|
||||
* UorbEnabledAutopilot
|
||||
*/
|
||||
class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
|
||||
{
|
||||
protected:
|
||||
// subscriptions
|
||||
uORB::SubscriptionPollable<manual_control_setpoint_s> _manual;
|
||||
uORB::SubscriptionPollable<parameter_update_s> _param_update;
|
||||
uORB::SubscriptionPollable<position_setpoint_triplet_s> _missionCmd;
|
||||
uORB::SubscriptionPollable<vehicle_attitude_s> _att;
|
||||
uORB::SubscriptionPollable<vehicle_angular_velocity_s> _angular_velocity;
|
||||
uORB::SubscriptionPollable<vehicle_attitude_setpoint_s> _attCmd;
|
||||
uORB::SubscriptionPollable<vehicle_global_position_s> _pos;
|
||||
uORB::SubscriptionPollable<vehicle_rates_setpoint_s> _ratesCmd;
|
||||
uORB::SubscriptionPollable<vehicle_status_s> _status;
|
||||
|
||||
// publications
|
||||
uORB::PublicationData<actuator_controls_s> _actuators{ORB_ID(actuator_controls_0)};
|
||||
|
||||
public:
|
||||
BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
|
||||
virtual ~BlockUorbEnabledAutopilot() = default;
|
||||
};
|
||||
|
||||
} // namespace control
|
||||
|
||||
@ -1,7 +0,0 @@
|
||||
#include <parameters/param.h>
|
||||
|
||||
// 16 is max name length
|
||||
PARAM_DEFINE_FLOAT(SEG_TH2V_P, 10.0f); // pitch to voltage
|
||||
PARAM_DEFINE_FLOAT(SEG_TH2V_I, 0.0f); // pitch integral to voltage
|
||||
PARAM_DEFINE_FLOAT(SEG_TH2V_I_MAX, 0.0f); // integral limiter
|
||||
PARAM_DEFINE_FLOAT(SEG_Q2V, 1.0f); // pitch rate to voltage
|
||||
@ -1,158 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: James Goppert
|
||||
*
|
||||
* 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 segway_main.cpp
|
||||
* @author James Goppert
|
||||
*
|
||||
* Segway controller using control library
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <parameters/param.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "BlockSegwayController.hpp"
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
/**
|
||||
* Deamon management function.
|
||||
*/
|
||||
extern "C" __EXPORT int segway_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of deamon.
|
||||
*/
|
||||
int segway_thread_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason) {
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
}
|
||||
|
||||
fprintf(stderr, "usage: segway {start|stop|status} [-p <additional params>]\n\n");
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_create().
|
||||
*/
|
||||
int segway_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
if (argc < 2) {
|
||||
usage("missing command");
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
if (thread_running) {
|
||||
warnx("already running");
|
||||
/* this is not an error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
|
||||
deamon_task = px4_task_spawn_cmd("segway",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 10,
|
||||
5120,
|
||||
segway_thread_main,
|
||||
(argv) ? (char *const *)&argv[2] : (char *const *)nullptr);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
thread_should_exit = true;
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
warnx("is running");
|
||||
|
||||
} else {
|
||||
warnx("not started");
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
return -1;
|
||||
}
|
||||
|
||||
int segway_thread_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
warnx("starting");
|
||||
|
||||
using namespace control;
|
||||
|
||||
BlockSegwayController autopilot;
|
||||
|
||||
thread_running = true;
|
||||
|
||||
while (!thread_should_exit) {
|
||||
autopilot.update();
|
||||
}
|
||||
|
||||
warnx("exiting.");
|
||||
|
||||
thread_running = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
Loading…
x
Reference in New Issue
Block a user