aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/ros/nodes/commander/commander.cpp
blob: fee32b55f9a8b5ac3997a9897285a231fdeef181 (plain) (blame)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
/****************************************************************************
 *
 *   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)),
	_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)),
	_vehicle_status_pub(_n.advertise<px4::vehicle_status>("vehicle_status", 10)),
	_parameter_update_pub(_n.advertise<px4::parameter_update>("parameter_update", 10)),
	_msg_parameter_update(),
	_msg_actuator_armed()
{
}

void Commander::ManualControlInputCallback(const px4::manual_control_setpointConstPtr &msg)
{
	px4::vehicle_control_mode msg_vehicle_control_mode;
	px4::vehicle_status msg_vehicle_status;

	/* fill vehicle control mode based on (faked) stick positions*/
	EvalSwitches(msg, msg_vehicle_status, msg_vehicle_control_mode);
	msg_vehicle_control_mode.timestamp = px4::get_time_micros();

	/* fill actuator armed */
	float arm_th = 0.95;
	_msg_actuator_armed.timestamp = px4::get_time_micros();

	if (_msg_actuator_armed.armed) {
		/* Check for disarm */
		if (msg->r < -arm_th && msg->z < (1 - arm_th)) {
			_msg_actuator_armed.armed = false;
			msg_vehicle_status.arming_state = msg_vehicle_status.ARMING_STATE_STANDBY;
		}

	} else {
		/* Check for arm */
		if (msg->r > arm_th && msg->z < (1 - arm_th)) {
			_msg_actuator_armed.armed = true;
			msg_vehicle_status.arming_state = msg_vehicle_status.ARMING_STATE_ARMED;
		}
	}

	/* fill vehicle status */
	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;

	_vehicle_control_mode_pub.publish(msg_vehicle_control_mode);
	_actuator_armed_pub.publish(_msg_actuator_armed);
	_vehicle_status_pub.publish(msg_vehicle_status);

	/* 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);
	}
}

void Commander::EvalSwitches(const px4::manual_control_setpointConstPtr &msg,
		px4::vehicle_status &msg_vehicle_status,
		px4::vehicle_control_mode &msg_vehicle_control_mode) {
	// XXX this is a minimal implementation. If more advanced functionalities are
	// needed consider a full port of the commander

	switch (msg->mode_switch) {
		case px4::manual_control_setpoint::SWITCH_POS_NONE:
		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;

		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;
		} 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;
		}
		break;
	}

}

int main(int argc, char **argv)
{
	ros::init(argc, argv, "commander");
	Commander m;
	ros::spin();
	return 0;
}