mixers/main.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2022-2023 RaccoonLab.
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, version 3.
7  *
8  * This program is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
11  * General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * Author: Dmitry Ponomarev <ponomarevda96@gmail.com>
17  */
18 
19 #include <ros/ros.h>
20 #include <sensor_msgs/Joy.h>
21 #include "mixer_babyshark.hpp"
22 #include "px4_v1.12.1_13070.hpp"
25 #include "mixer_direct.hpp"
26 
27 
28 int main(int argc, char **argv){
29  ros::init(argc, argv, "mixer_node");
32  }
33 
34  ros::NodeHandle node_handler("inno_vtol_reverse_mixer");
35  std::string mixer;
36  if(!node_handler.getParam("mixer", mixer)){
37  ROS_ERROR("ReverseMixer: There is no `mixer` parameter.");
38  return -1;
39  }
40 
41  std::unique_ptr<BaseReverseMixer> reverseMixer;
42  if (mixer == "babyshark_standard_vtol_mixer") {
43  reverseMixer = std::make_unique<BabysharkReverseMixer>(node_handler);
44  } else if (mixer == "vtol_13070_mixer") {
45  reverseMixer = std::make_unique<PX4_V_1_12_1_Airframe_13070_to_VTOL>(node_handler);
46  } else if (mixer == "px4_v1_14_0_vtol_13000_mixer") {
47  reverseMixer = std::make_unique<PX4_V_1_14_0_Airframe_13000_4_motors>(node_handler);
48  } else if (mixer == "px4_v1_14_0_vtol_13000_8_motors_mixer") {
49  reverseMixer = std::make_unique<PX4_V_1_14_0_Airframe_13000_8_motors>(node_handler);
50  } else if (mixer == "direct_mixer") {
51  reverseMixer = std::make_unique<DirectMixer>(node_handler);
52  } else {
53  ROS_ERROR("ReverseMixer: Wrong `/uav/sim_params/mixer` parameter.");
54  return -1;
55  }
56  ROS_INFO_STREAM("ReverseMixer: mixer is " << mixer.c_str());
57 
58  if (reverseMixer->init() == -1){
59  ROS_ERROR("Shutdown.");
60  ros::shutdown();
61  return -1;
62  }
63 
64  ros::spin();
65  return 0;
66 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
ros::shutdown
ROSCPP_DECL void shutdown()
ros::console::set_logger_level
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
main
int main(int argc, char **argv)
Definition: mixers/main.cpp:28
mixer_direct.hpp
mixer_babyshark.hpp
ros::console::levels::Debug
Debug
px4_v1.14.0_13000_vtol_4_motors.hpp
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
px4_v1.14.0_13000_vtol_8_motors.hpp
ros::console::notifyLoggerLevelsChanged
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
px4_v1.12.1_13070.hpp
ROS_ERROR
#define ROS_ERROR(...)
ros::spin
ROSCPP_DECL void spin()
ROSCONSOLE_DEFAULT_NAME
#define ROSCONSOLE_DEFAULT_NAME
ros::NodeHandle


inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35