From 1f8fd5d1207512711c47859e06ac23c340be1551 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 30 Dec 2014 09:13:20 +0100 Subject: [PATCH] new dummy attitude estimator skeleton --- CMakeLists.txt | 8 +-- launch/multicopter.launch | 2 +- .../attitude_estimator/attitude_estimator.cpp | 70 +++++++++++++++++++ .../attitude_estimator.h} | 33 +++++---- .../ros/nodes/manual_input/manual_input.cpp | 3 +- 5 files changed, 92 insertions(+), 24 deletions(-) create mode 100644 src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp rename src/platforms/ros/nodes/{att_estimator/att_estimator.cpp => attitude_estimator/attitude_estimator.h} (81%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2588680270..d506cadb17 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -177,10 +177,10 @@ target_link_libraries(mc_att_control ) ## Attitude Estimator dummy -add_executable(att_estimator - src/platforms/ros/nodes/att_estimator/att_estimator.cpp) -add_dependencies(att_estimator px4_generate_messages_cpp) -target_link_libraries(att_estimator +add_executable(attitude_estimator + src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp) +add_dependencies(attitude_estimator px4_generate_messages_cpp) +target_link_libraries(attitude_estimator ${catkin_LIBRARIES} px4 ) diff --git a/launch/multicopter.launch b/launch/multicopter.launch index 5db0e6415d..8cc89450dd 100644 --- a/launch/multicopter.launch +++ b/launch/multicopter.launch @@ -2,7 +2,7 @@ - + diff --git a/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp new file mode 100644 index 0000000000..7504091ebb --- /dev/null +++ b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.cpp @@ -0,0 +1,70 @@ +/**************************************************************************** + * + * 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 att_estimator.cpp + * Dummy attitude estimator that forwards attitude from gazebo to px4 topic + * + * @author Thomas Gubler +*/ + +#include "attitude_estimator.h" + +#include + +AttitudeEstimator::AttitudeEstimator() : + _n(), + _sub_modelstates(_n.subscribe("joy", 10, &AttitudeEstimator::ModelStatesCallback, this)), + _vehicle_attitude_pub(_n.advertise("vehicle_attitude", 10)) +{ +} + +void AttitudeEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstPtr& msg) +{ + px4::vehicle_attitude msg_out; + + /* Fill px4 attitude topic with contents from modelstates topic */ + //XXX + + _vehicle_attitude_pub.publish(msg_out); +} + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "attitude_estimator"); + AttitudeEstimator m; + + ros::spin(); + + return 0; +} diff --git a/src/platforms/ros/nodes/att_estimator/att_estimator.cpp b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.h similarity index 81% rename from src/platforms/ros/nodes/att_estimator/att_estimator.cpp rename to src/platforms/ros/nodes/attitude_estimator/attitude_estimator.h index fa021fff01..e3326b7152 100644 --- a/src/platforms/ros/nodes/att_estimator/att_estimator.cpp +++ b/src/platforms/ros/nodes/attitude_estimator/attitude_estimator.h @@ -32,7 +32,7 @@ ****************************************************************************/ /** - * @file att_estimator.cpp + * @file att_estimator.h * Dummy attitude estimator that forwards attitude from gazebo to px4 topic * * @author Thomas Gubler @@ -40,23 +40,22 @@ #include "ros/ros.h" #include -//#include "std_msgs/String.h" -/** - * This tutorial demonstrates simple receipt of messages over the ROS system. - */ -void chatterCallback(const gazebo_msgs::ModelStates &msg) -{ - // try to read out message here -} +class AttitudeEstimator { +public: + AttitudeEstimator(); -int main(int argc, char **argv) -{ - ros::init(argc, argv, "att_estimator"); - ros::NodeHandle n; - ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback); + ~AttitudeEstimator() {} - ros::spin(); +protected: + /** + * Takes ROS joystick message and converts/publishes to px4 manual control setpoint topic + */ + void ModelStatesCallback(const gazebo_msgs::ModelStatesConstPtr& msg); - return 0; -} + ros::NodeHandle _n; + ros::Subscriber _sub_modelstates; + ros::Publisher _vehicle_attitude_pub; + + +}; diff --git a/src/platforms/ros/nodes/manual_input/manual_input.cpp b/src/platforms/ros/nodes/manual_input/manual_input.cpp index 531ffa6407..41e597ab79 100644 --- a/src/platforms/ros/nodes/manual_input/manual_input.cpp +++ b/src/platforms/ros/nodes/manual_input/manual_input.cpp @@ -45,11 +45,10 @@ ManualInput::ManualInput() : _n(), _sub_joy(_n.subscribe("joy", 10, &ManualInput::JoyCallback, this)), - _man_ctrl_sp_pub(_n.advertise("manual_control_setpoint", 1000)) + _man_ctrl_sp_pub(_n.advertise("manual_control_setpoint", 10)) { } - void ManualInput::JoyCallback(const sensor_msgs::JoyConstPtr& msg) { px4::manual_control_setpoint msg_out;