2014-12-30 12:27:29 +01:00
|
|
|
/****************************************************************************
|
|
|
|
|
*
|
|
|
|
|
* Copyright (c) 2014 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 commander.cpp
|
|
|
|
|
* Dummy commander node that publishes the various status topics
|
|
|
|
|
*
|
|
|
|
|
* @author Thomas Gubler <thomasgubler@gmail.com>
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
#include "commander.h"
|
|
|
|
|
|
|
|
|
|
#include <platforms/px4_middleware.h>
|
|
|
|
|
|
|
|
|
|
Commander::Commander() :
|
|
|
|
|
_n(),
|
|
|
|
|
_man_ctrl_sp_sub(_n.subscribe("manual_control_setpoint", 10, &Commander::ManualControlInputCallback, this)),
|
2015-02-14 16:49:06 +01:00
|
|
|
_offboard_control_mode_sub(_n.subscribe("offboard_control_mode", 10, &Commander::OffboardControlModeCallback, this)),
|
2014-12-30 12:27:29 +01:00
|
|
|
_vehicle_control_mode_pub(_n.advertise<px4::vehicle_control_mode>("vehicle_control_mode", 10)),
|
|
|
|
|
_actuator_armed_pub(_n.advertise<px4::actuator_armed>("actuator_armed", 10)),
|
2015-01-02 09:08:49 +01:00
|
|
|
_vehicle_status_pub(_n.advertise<px4::vehicle_status>("vehicle_status", 10)),
|
|
|
|
|
_parameter_update_pub(_n.advertise<px4::parameter_update>("parameter_update", 10)),
|
2015-01-02 16:11:16 +01:00
|
|
|
_msg_parameter_update(),
|
2015-01-29 14:23:03 +01:00
|
|
|
_msg_actuator_armed(),
|
2015-02-14 16:49:06 +01:00
|
|
|
_msg_vehicle_control_mode(),
|
2015-04-03 11:14:40 +02:00
|
|
|
_msg_vehicle_status(),
|
2015-02-15 18:31:49 +01:00
|
|
|
_msg_offboard_control_mode(),
|
|
|
|
|
_got_manual_control(false)
|
2014-12-30 12:27:29 +01:00
|
|
|
{
|
2015-02-15 18:31:49 +01:00
|
|
|
|
|
|
|
|
/* Default to offboard control: when no joystick is connected offboard control should just work */
|
|
|
|
|
|
2014-12-30 12:27:29 +01:00
|
|
|
}
|
|
|
|
|
|
2015-01-08 08:15:44 +01:00
|
|
|
void Commander::ManualControlInputCallback(const px4::manual_control_setpointConstPtr &msg)
|
2014-12-30 12:27:29 +01:00
|
|
|
{
|
2015-02-15 18:31:49 +01:00
|
|
|
_got_manual_control = true;
|
2014-12-30 12:27:29 +01:00
|
|
|
|
2015-01-29 13:38:39 +01:00
|
|
|
/* fill vehicle control mode based on (faked) stick positions*/
|
2015-04-03 11:14:40 +02:00
|
|
|
EvalSwitches(msg, _msg_vehicle_status, _msg_vehicle_control_mode);
|
2015-01-29 14:23:03 +01:00
|
|
|
_msg_vehicle_control_mode.timestamp = px4::get_time_micros();
|
2014-12-30 12:27:29 +01:00
|
|
|
|
|
|
|
|
/* fill actuator armed */
|
2015-01-02 16:11:16 +01:00
|
|
|
float arm_th = 0.95;
|
|
|
|
|
_msg_actuator_armed.timestamp = px4::get_time_micros();
|
2015-01-08 08:15:44 +01:00
|
|
|
|
2015-01-02 16:11:16 +01:00
|
|
|
if (_msg_actuator_armed.armed) {
|
|
|
|
|
/* Check for disarm */
|
2015-01-08 08:15:44 +01:00
|
|
|
if (msg->r < -arm_th && msg->z < (1 - arm_th)) {
|
2015-01-02 16:11:16 +01:00
|
|
|
_msg_actuator_armed.armed = false;
|
2015-01-29 14:23:03 +01:00
|
|
|
_msg_vehicle_control_mode.flag_armed = false;
|
2015-04-03 11:14:40 +02:00
|
|
|
_msg_vehicle_status.arming_state = _msg_vehicle_status.ARMING_STATE_STANDBY;
|
2015-01-02 16:11:16 +01:00
|
|
|
}
|
2015-01-08 08:15:44 +01:00
|
|
|
|
2015-01-02 16:11:16 +01:00
|
|
|
} else {
|
|
|
|
|
/* Check for arm */
|
2015-01-08 08:15:44 +01:00
|
|
|
if (msg->r > arm_th && msg->z < (1 - arm_th)) {
|
2015-01-02 16:11:16 +01:00
|
|
|
_msg_actuator_armed.armed = true;
|
2015-01-29 14:23:03 +01:00
|
|
|
_msg_vehicle_control_mode.flag_armed = true;
|
2015-04-03 11:14:40 +02:00
|
|
|
_msg_vehicle_status.arming_state = _msg_vehicle_status.ARMING_STATE_ARMED;
|
2015-01-02 16:11:16 +01:00
|
|
|
}
|
|
|
|
|
}
|
2014-12-30 12:27:29 +01:00
|
|
|
|
|
|
|
|
/* fill vehicle status */
|
2015-04-03 11:14:40 +02:00
|
|
|
_msg_vehicle_status.timestamp = px4::get_time_micros();
|
|
|
|
|
_msg_vehicle_status.hil_state = _msg_vehicle_status.HIL_STATE_OFF;
|
|
|
|
|
_msg_vehicle_status.hil_state = _msg_vehicle_status.VEHICLE_TYPE_QUADROTOR;
|
|
|
|
|
_msg_vehicle_status.is_rotary_wing = true;
|
2014-12-30 12:27:29 +01:00
|
|
|
|
2015-01-29 14:23:03 +01:00
|
|
|
_vehicle_control_mode_pub.publish(_msg_vehicle_control_mode);
|
2015-01-02 16:11:16 +01:00
|
|
|
_actuator_armed_pub.publish(_msg_actuator_armed);
|
2015-04-03 11:14:40 +02:00
|
|
|
_vehicle_status_pub.publish(_msg_vehicle_status);
|
2015-01-02 09:08:49 +01:00
|
|
|
|
|
|
|
|
/* Fill parameter update */
|
|
|
|
|
if (px4::get_time_micros() - _msg_parameter_update.timestamp > 1e6) {
|
|
|
|
|
_msg_parameter_update.timestamp = px4::get_time_micros();
|
|
|
|
|
_parameter_update_pub.publish(_msg_parameter_update);
|
|
|
|
|
}
|
2014-12-30 12:27:29 +01:00
|
|
|
}
|
|
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
void Commander::SetOffboardControl(const px4::offboard_control_mode &msg_offboard_control_mode,
|
2015-10-19 13:36:00 +02:00
|
|
|
px4::vehicle_control_mode &msg_vehicle_control_mode)
|
2015-02-15 18:31:49 +01:00
|
|
|
{
|
|
|
|
|
msg_vehicle_control_mode.flag_control_manual_enabled = false;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_offboard_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_auto_enabled = false;
|
2015-01-29 13:38:39 +01:00
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_rates_enabled = !msg_offboard_control_mode.ignore_bodyrate ||
|
2015-10-19 13:36:00 +02:00
|
|
|
!msg_offboard_control_mode.ignore_attitude ||
|
|
|
|
|
!msg_offboard_control_mode.ignore_position ||
|
|
|
|
|
!msg_offboard_control_mode.ignore_velocity ||
|
|
|
|
|
!msg_offboard_control_mode.ignore_acceleration_force;
|
2015-02-14 16:49:06 +01:00
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_attitude_enabled = !msg_offboard_control_mode.ignore_attitude ||
|
2015-10-19 13:36:00 +02:00
|
|
|
!msg_offboard_control_mode.ignore_position ||
|
|
|
|
|
!msg_offboard_control_mode.ignore_velocity ||
|
|
|
|
|
!msg_offboard_control_mode.ignore_acceleration_force;
|
2015-02-14 16:49:06 +01:00
|
|
|
|
|
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_velocity_enabled = !msg_offboard_control_mode.ignore_velocity ||
|
2015-10-19 13:36:00 +02:00
|
|
|
!msg_offboard_control_mode.ignore_position;
|
2015-02-14 16:49:06 +01:00
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_climb_rate_enabled = !msg_offboard_control_mode.ignore_velocity ||
|
2015-10-19 13:36:00 +02:00
|
|
|
!msg_offboard_control_mode.ignore_position;
|
2015-02-14 16:49:06 +01:00
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_position_enabled = !msg_offboard_control_mode.ignore_position;
|
2015-02-14 16:49:06 +01:00
|
|
|
|
2015-07-03 14:36:55 +02:00
|
|
|
msg_vehicle_control_mode.flag_control_altitude_enabled = !msg_offboard_control_mode.ignore_velocity ||
|
2015-10-19 13:36:00 +02:00
|
|
|
!msg_offboard_control_mode.ignore_position;
|
2015-02-15 18:31:49 +01:00
|
|
|
}
|
2015-02-14 16:49:06 +01:00
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
void Commander::EvalSwitches(const px4::manual_control_setpointConstPtr &msg,
|
2015-10-19 13:36:00 +02:00
|
|
|
px4::vehicle_status &msg_vehicle_status,
|
|
|
|
|
px4::vehicle_control_mode &msg_vehicle_control_mode)
|
|
|
|
|
{
|
2015-02-15 18:31:49 +01:00
|
|
|
// XXX this is a minimal implementation. If more advanced functionalities are
|
|
|
|
|
// needed consider a full port of the commander
|
|
|
|
|
|
|
|
|
|
|
2015-10-19 13:36:00 +02:00
|
|
|
if (msg->offboard_switch == px4::manual_control_setpoint::SWITCH_POS_ON) {
|
2015-02-15 18:31:49 +01:00
|
|
|
SetOffboardControl(_msg_offboard_control_mode, msg_vehicle_control_mode);
|
2015-02-14 16:49:06 +01:00
|
|
|
return;
|
|
|
|
|
}
|
|
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_offboard_enabled = false;
|
|
|
|
|
|
2015-01-29 13:38:39 +01:00
|
|
|
switch (msg->mode_switch) {
|
2015-10-19 13:36:00 +02:00
|
|
|
case px4::manual_control_setpoint::SWITCH_POS_NONE:
|
2015-01-29 13:38:39 +01:00
|
|
|
ROS_WARN("Joystick button mapping error, main mode not set");
|
|
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
case px4::manual_control_setpoint::SWITCH_POS_OFF: // MANUAL
|
|
|
|
|
msg_vehicle_status.main_state = msg_vehicle_status.MAIN_STATE_MANUAL;
|
|
|
|
|
msg_vehicle_status.nav_state = msg_vehicle_status.NAVIGATION_STATE_MANUAL;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_manual_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_rates_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_attitude_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_altitude_enabled = false;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_climb_rate_enabled = false;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_position_enabled = false;
|
2015-01-29 14:09:25 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_velocity_enabled = false;
|
2015-01-29 13:38:39 +01:00
|
|
|
|
|
|
|
|
break;
|
|
|
|
|
|
|
|
|
|
case px4::manual_control_setpoint::SWITCH_POS_MIDDLE: // ASSIST
|
|
|
|
|
if (msg->posctl_switch == px4::manual_control_setpoint::SWITCH_POS_ON) {
|
|
|
|
|
msg_vehicle_status.main_state = msg_vehicle_status.MAIN_STATE_POSCTL;
|
|
|
|
|
msg_vehicle_status.nav_state = msg_vehicle_status.NAVIGATION_STATE_POSCTL;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_manual_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_rates_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_attitude_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_altitude_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_climb_rate_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_position_enabled = true;
|
2015-01-29 14:09:25 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_velocity_enabled = true;
|
2015-10-19 13:36:00 +02:00
|
|
|
|
2015-01-29 13:38:39 +01:00
|
|
|
} else {
|
|
|
|
|
msg_vehicle_status.main_state = msg_vehicle_status.MAIN_STATE_ALTCTL;
|
|
|
|
|
msg_vehicle_status.nav_state = msg_vehicle_status.NAVIGATION_STATE_ALTCTL;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_manual_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_rates_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_attitude_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_altitude_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_climb_rate_enabled = true;
|
|
|
|
|
msg_vehicle_control_mode.flag_control_position_enabled = false;
|
2015-01-29 14:09:25 +01:00
|
|
|
msg_vehicle_control_mode.flag_control_velocity_enabled = false;
|
2015-01-29 13:38:39 +01:00
|
|
|
}
|
2015-10-19 13:36:00 +02:00
|
|
|
|
2015-01-29 13:38:39 +01:00
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
2015-02-14 16:49:06 +01:00
|
|
|
void Commander::OffboardControlModeCallback(const px4::offboard_control_modeConstPtr &msg)
|
|
|
|
|
{
|
|
|
|
|
_msg_offboard_control_mode = *msg;
|
2015-02-15 18:31:49 +01:00
|
|
|
|
|
|
|
|
/* Force system into offboard control mode */
|
|
|
|
|
if (!_got_manual_control) {
|
|
|
|
|
SetOffboardControl(_msg_offboard_control_mode, _msg_vehicle_control_mode);
|
2015-10-19 13:36:00 +02:00
|
|
|
|
2015-04-03 11:14:40 +02:00
|
|
|
_msg_vehicle_status.timestamp = px4::get_time_micros();
|
|
|
|
|
_msg_vehicle_status.hil_state = _msg_vehicle_status.HIL_STATE_OFF;
|
|
|
|
|
_msg_vehicle_status.hil_state = _msg_vehicle_status.VEHICLE_TYPE_QUADROTOR;
|
|
|
|
|
_msg_vehicle_status.is_rotary_wing = true;
|
|
|
|
|
_msg_vehicle_status.arming_state = _msg_vehicle_status.ARMING_STATE_ARMED;
|
2015-10-19 13:36:00 +02:00
|
|
|
|
2015-02-22 12:35:45 +01:00
|
|
|
|
|
|
|
|
_msg_actuator_armed.armed = true;
|
|
|
|
|
_msg_actuator_armed.timestamp = px4::get_time_micros();
|
|
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
_msg_vehicle_control_mode.timestamp = px4::get_time_micros();
|
2015-02-22 12:35:45 +01:00
|
|
|
_msg_vehicle_control_mode.flag_armed = true;
|
2015-10-19 13:36:00 +02:00
|
|
|
|
2015-02-22 12:35:45 +01:00
|
|
|
|
2015-02-15 18:31:49 +01:00
|
|
|
_vehicle_control_mode_pub.publish(_msg_vehicle_control_mode);
|
2015-02-22 12:35:45 +01:00
|
|
|
_actuator_armed_pub.publish(_msg_actuator_armed);
|
2015-04-03 11:14:40 +02:00
|
|
|
_vehicle_status_pub.publish(_msg_vehicle_status);
|
2015-02-15 18:31:49 +01:00
|
|
|
}
|
2015-02-14 16:49:06 +01:00
|
|
|
}
|
|
|
|
|
|
2014-12-30 12:27:29 +01:00
|
|
|
int main(int argc, char **argv)
|
|
|
|
|
{
|
2015-01-08 08:15:44 +01:00
|
|
|
ros::init(argc, argv, "commander");
|
|
|
|
|
Commander m;
|
|
|
|
|
ros::spin();
|
|
|
|
|
return 0;
|
2014-12-30 12:27:29 +01:00
|
|
|
}
|