Browse Source

Land detector: Add mode for rovers

sbg
Lorenz Meier 8 years ago
parent
commit
5f135acf33
  1. 15
      posix-configs/SITL/init/ekf2/rover
  2. 1
      src/modules/land_detector/CMakeLists.txt
  3. 1
      src/modules/land_detector/LandDetector.h
  4. 80
      src/modules/land_detector/RoverLandDetector.cpp
  5. 73
      src/modules/land_detector/RoverLandDetector.h
  6. 4
      src/modules/land_detector/land_detector_main.cpp

15
posix-configs/SITL/init/ekf2/rover

@ -24,14 +24,19 @@ param set SENS_DPRES_OFF 0.001 @@ -24,14 +24,19 @@ param set SENS_DPRES_OFF 0.001
param set SENS_BOARD_X_OFF 0.000001
param set COM_RC_IN_MODE 1
param set NAV_DLL_ACT 2
param set NAV_ACC_RAD 15.0
param set NAV_LOITER_RAD 50
param set MIS_LTRMIN_ALT 30
param set MIS_TAKEOFF_ALT 30
param set FW_THR_IDLE 0.8
param set NAV_ACC_RAD 2.0
param set NAV_LOITER_RAD 10
param set MIS_LTRMIN_ALT 0.01
param set MIS_TAKEOFF_ALT 0.01
param set FW_THR_IDLE 0.0
param set EKF2_GBIAS_INIT 0.01
param set EKF2_ANGERR_INIT 0.01
param set EKF2_MAG_TYPE 1
param set FW_AIRSPD_MIN 0
param set FW_AIRSPD_TRIM 6
param set FW_AIRSPD_MAX 8
param set FW_PR_I 0.0
param set FW_RR_I 0.0
replay tryapplyparams
simulator start -s
tone_alarm start

1
src/modules/land_detector/CMakeLists.txt

@ -41,6 +41,7 @@ px4_add_module( @@ -41,6 +41,7 @@ px4_add_module(
MulticopterLandDetector.cpp
FixedwingLandDetector.cpp
VtolLandDetector.cpp
RoverLandDetector.cpp
DEPENDS
platforms__common
)

1
src/modules/land_detector/LandDetector.h

@ -44,6 +44,7 @@ Land detector interface for multicopter, fixedwing and VTOL implementations. @@ -44,6 +44,7 @@ Land detector interface for multicopter, fixedwing and VTOL implementations.
#include <px4_workqueue.h>
#include <systemlib/hysteresis/hysteresis.h>
#include <systemlib/param/param.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_land_detected.h>

80
src/modules/land_detector/RoverLandDetector.cpp

@ -0,0 +1,80 @@ @@ -0,0 +1,80 @@
/****************************************************************************
*
* Copyright (c) 2013-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 RoverLandDetector.cpp
* Land detection algorithm for Rovers
*
* @author Roman Bapst <bapstroma@gmail.com>
* @author Julian Oes <julian@oes.ch>
*/
#include <drivers/drv_hrt.h>
#include "RoverLandDetector.h"
namespace land_detector
{
RoverLandDetector::RoverLandDetector() : LandDetector()
{
}
void RoverLandDetector::_initialize_topics()
{
}
void RoverLandDetector::_update_topics()
{
}
bool RoverLandDetector::_get_ground_contact_state()
{
return false;
}
bool RoverLandDetector::_get_landed_state()
{
return false;
}
bool RoverLandDetector::_get_freefall_state()
{
return false;
}
void RoverLandDetector::_update_params()
{
}
}

73
src/modules/land_detector/RoverLandDetector.h

@ -0,0 +1,73 @@ @@ -0,0 +1,73 @@
/****************************************************************************
*
* Copyright (c) 2013-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 RoverLandDetector.h
* Land detection implementation for VTOL also called hybrids.
*
* @author Roman Bapst <bapstr@gmail.com>
* @author Julian Oes <julian@oes.ch>
*/
#pragma once
#include <uORB/topics/airspeed.h>
#include "LandDetector.h"
namespace land_detector
{
class RoverLandDetector : public LandDetector
{
public:
RoverLandDetector();
protected:
virtual void _initialize_topics() override;
virtual void _update_params() override;
virtual void _update_topics() override;
virtual bool _get_landed_state() override;
virtual bool _get_ground_contact_state() override;
virtual bool _get_freefall_state() override;
private:
};
} // namespace land_detector

4
src/modules/land_detector/land_detector_main.cpp

@ -55,6 +55,7 @@ @@ -55,6 +55,7 @@
#include "FixedwingLandDetector.h"
#include "MulticopterLandDetector.h"
#include "VtolLandDetector.h"
#include "RoverLandDetector.h"
namespace land_detector
@ -122,6 +123,9 @@ static int land_detector_start(const char *mode) @@ -122,6 +123,9 @@ static int land_detector_start(const char *mode)
} else if (!strcmp(mode, "vtol")) {
land_detector_task = new VtolLandDetector();
} else if (!strcmp(mode, "rover")) {
land_detector_task = new RoverLandDetector();
} else {
PX4_WARN("[mode] must be either 'fixedwing', 'multicopter', or 'vtol'");
return -1;

Loading…
Cancel
Save