You cannot select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

106 lines
2.6 KiB
C++

4 years ago
#include "class_model/mission.h"
3 years ago
#include "class_model/choose_leader.h"
#include "class_model/PubInfo.h"
#include "yaml-cpp/yaml.h"
4 years ago
int main(int argc, char **argv) {
// Init ROS node
ros::init(argc, argv, "drone1_node");
// reate Assync spiner
ros::AsyncSpinner spinner(0);
spinner.start();
3 years ago
ModeClass mode_object;
ControlClass control_object;
ReceiverClass receiver_object;
MissionClass mission_object;
CommandClass command_object;
SelectClass select_formation;
PubInfoClass PubInfo_object;
3 years ago
// SelectionClass selection_object;
3 years ago
YAML::Node config = YAML::LoadFile("/home/dodo/ardupilot_ws/src/class_model/src/config.yaml"); //reading yaml parameter(target point)
3 years ago
mode_object.set_Mode("GUIDED");
control_object.arm();
control_object.takeoff(4.5);
3 years ago
sleep(2);
3 years ago
3 years ago
// selection_object.choose_leader();
3 years ago
// mission_object.start(); //default hover in goose formation
INFO msg;
msg.type = "V_formation";
msg.mission = "fly2target";
3 years ago
while(ros::ok()){
//json_object.get_command(); //for follower
//select_formation.goose_formation();
PubInfo_object.pub_info(msg);
3 years ago
}
3 years ago
ros::waitForShutdown();
return 0;
}
3 years ago
/*
ThreadGPSClass gps_object;
4 years ago
ModeClass mode_object;
ControlClass control_object;
SelectClass select_formation;
ReceiverClass receiver_object;
MissionClass mission_object;
CommandClass command_object;
3 years ago
4 years ago
std::string type = "";
mode_object.set_Mode("GUIDED");
control_object.arm();
control_object.takeoff(4.5);
sleep(5);
while(ros::ok()){
3 years ago
// type = receiver_object.check_command();
4 years ago
// // ROS_INFO("%s",type.c_str());
4 years ago
// if(type == "" || type == "init"){
// select_formation.goose_formation();
// ROS_INFO("init formation");
// }else if(type == "line"){
// select_formation.line_formation();
// // ROS_INFO("line foemation");
// }else if(type == "row"){
// select_formation.row_formation();
// }else if(type == "circle"){
// select_formation.circle_formation();
// }else if(type == "stop"){
// select_formation.stop();
// }else if(type == "land"){
// mode_object.set_Mode("LAND");
// }
4 years ago
//mission_object.cruise(20,20);
4 years ago
select_formation.goose_formation(5,0);
4 years ago
// }else if (type == "hex"){
// select_formation.Hex_formation();
// }
4 years ago
select_formation.row_formation(-5,0);
4 years ago
sleep(0.5);
// command_object.set_velocity(0 ,0 ,0,0,1);
if(type == "stop"){
select_formation.stop();
}else if(type == "land"){
mode_object.set_Mode("LAND");
}
}
3 years ago
*/