aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--CMakeLists.txt8
-rw-r--r--src/platforms/px4_middleware.h4
-rw-r--r--src/platforms/ros/nodes/commander/commander.cpp96
-rw-r--r--src/platforms/ros/nodes/commander/commander.h62
-rw-r--r--src/platforms/ros/nodes/manual_input/manual_input.cpp7
-rw-r--r--src/platforms/ros/nodes/manual_input/manual_input.h2
6 files changed, 175 insertions, 4 deletions
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 220cd762b..6312fa055 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -203,6 +203,14 @@ target_link_libraries(mc_mixer
px4
)
+## Commander
+add_executable(commander
+ src/platforms/ros/nodes/commander/commander.cpp)
+add_dependencies(manual_input px4_generate_messages_cpp)
+target_link_libraries(commander
+ ${catkin_LIBRARIES}
+ px4
+)
#############
## Install ##
diff --git a/src/platforms/px4_middleware.h b/src/platforms/px4_middleware.h
index a8f3ad666..54050de8b 100644
--- a/src/platforms/px4_middleware.h
+++ b/src/platforms/px4_middleware.h
@@ -42,6 +42,10 @@
#include <stdint.h>
#include <unistd.h>
+#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
+#define __EXPORT
+#endif
+
namespace px4
{
diff --git a/src/platforms/ros/nodes/commander/commander.cpp b/src/platforms/ros/nodes/commander/commander.cpp
new file mode 100644
index 000000000..f767bbb36
--- /dev/null
+++ b/src/platforms/ros/nodes/commander/commander.cpp
@@ -0,0 +1,96 @@
+/****************************************************************************
+ *
+ * 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 <px4/manual_control_setpoint.h>
+#include <px4/vehicle_control_mode.h>
+#include <px4/actuator_armed.h>
+#include <px4/vehicle_status.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))
+{
+}
+
+void Commander::ManualControlInputCallback(const px4::manual_control_setpointConstPtr& msg)
+{
+ px4::vehicle_control_mode msg_vehicle_control_mode;
+ px4::actuator_armed msg_actuator_armed;
+ px4::vehicle_status msg_vehicle_status;
+
+ /* fill vehicle control mode */
+ //XXX hardcoded
+ msg_vehicle_control_mode.timestamp = px4::get_time_micros();
+ 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;
+
+ /* fill actuator armed */
+ //XXX hardcoded
+ msg_actuator_armed.timestamp = px4::get_time_micros();
+ msg_actuator_armed.armed = true;
+
+ /* fill vehicle status */
+ //XXX hardcoded
+ msg_vehicle_status.timestamp = px4::get_time_micros();
+ msg_vehicle_status.main_state = msg_vehicle_status.MAIN_STATE_MANUAL;
+ msg_vehicle_status.nav_state = msg_vehicle_status.NAVIGATION_STATE_MANUAL;
+ msg_vehicle_status.arming_state = msg_vehicle_status.ARMING_STATE_ARMED;
+ msg_vehicle_status.hil_state = msg_vehicle_status.HIL_STATE_OFF;
+ msg_vehicle_status.hil_state = msg_vehicle_status.VEHICLE_TYPE_QUADROTOR;
+
+ _vehicle_control_mode_pub.publish(msg_vehicle_control_mode);
+ _actuator_armed_pub.publish(msg_actuator_armed);
+ _vehicle_status_pub.publish(msg_vehicle_status);
+}
+
+int main(int argc, char **argv)
+{
+ ros::init(argc, argv, "commander");
+ Commander m;
+ ros::spin();
+ return 0;
+}
diff --git a/src/platforms/ros/nodes/commander/commander.h b/src/platforms/ros/nodes/commander/commander.h
new file mode 100644
index 000000000..d7fe0a4ca
--- /dev/null
+++ b/src/platforms/ros/nodes/commander/commander.h
@@ -0,0 +1,62 @@
+/****************************************************************************
+ *
+ * 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.h
+ * Dummy commander node that publishes the various status topics
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+*/
+
+#include "ros/ros.h"
+#include <px4/manual_control_setpoint.h>
+
+class Commander {
+public:
+ Commander();
+
+ ~Commander() {}
+
+protected:
+ /**
+ * Based on manual control input the status will be set
+ */
+ void ManualControlInputCallback(const px4::manual_control_setpointConstPtr& msg);
+
+ ros::NodeHandle _n;
+ ros::Subscriber _man_ctrl_sp_sub;
+ ros::Publisher _vehicle_control_mode_pub;
+ ros::Publisher _actuator_armed_pub;
+ ros::Publisher _vehicle_status_pub;
+
+};
diff --git a/src/platforms/ros/nodes/manual_input/manual_input.cpp b/src/platforms/ros/nodes/manual_input/manual_input.cpp
index 2ee2dadbc..b125bb180 100644
--- a/src/platforms/ros/nodes/manual_input/manual_input.cpp
+++ b/src/platforms/ros/nodes/manual_input/manual_input.cpp
@@ -41,10 +41,11 @@
#include "manual_input.h"
#include <px4/manual_control_setpoint.h>
+#include <platforms/px4_middleware.h>
ManualInput::ManualInput() :
_n(),
- _sub_joy(_n.subscribe("joy", 10, &ManualInput::JoyCallback, this)),
+ joy_sub(_n.subscribe("joy", 10, &ManualInput::JoyCallback, this)),
_man_ctrl_sp_pub(_n.advertise<px4::manual_control_setpoint>("manual_control_setpoint", 10))
{
/* Load parameters, default values work for Microsoft XBox Controller */
@@ -87,6 +88,8 @@ void ManualInput::JoyCallback(const sensor_msgs::JoyConstPtr& msg)
msg_out.acro_switch = 0;
msg_out.offboard_switch = 0;
+ msg_out.timestamp = px4::get_time_micros();
+
_man_ctrl_sp_pub.publish(msg_out);
}
@@ -99,8 +102,6 @@ int main(int argc, char **argv)
{
ros::init(argc, argv, "manual_input");
ManualInput m;
-
ros::spin();
-
return 0;
}
diff --git a/src/platforms/ros/nodes/manual_input/manual_input.h b/src/platforms/ros/nodes/manual_input/manual_input.h
index fbe635cf2..22a158985 100644
--- a/src/platforms/ros/nodes/manual_input/manual_input.h
+++ b/src/platforms/ros/nodes/manual_input/manual_input.h
@@ -59,7 +59,7 @@ protected:
void MapAxis(const sensor_msgs::JoyConstPtr& msg, int map_index, double scale, double offset, float &out);
ros::NodeHandle _n;
- ros::Subscriber _sub_joy;
+ ros::Subscriber joy_sub;
ros::Publisher _man_ctrl_sp_pub;
/* Parameters */