diff --git a/class_model/CMakeLists.txt b/class_model/CMakeLists.txt index bfde0d3..27a4360 100755 --- a/class_model/CMakeLists.txt +++ b/class_model/CMakeLists.txt @@ -309,6 +309,13 @@ add_executable(bio_main3 src/bio_main3.cpp) target_link_libraries(bio_main3 ${catkin_LIBRARIES} follower_lib Leader_lib /home/dodo/ardupilot_ws/src/class_model/libs/libyaml-cpp.a) add_dependencies(bio_main3 class_model_generate_messages_cpp) +add_executable(bio_main4 src/bio_main4.cpp) +target_link_libraries(bio_main4 ${catkin_LIBRARIES} follower_lib Leader_lib /home/dodo/ardupilot_ws/src/class_model/libs/libyaml-cpp.a) +add_dependencies(bio_main4 class_model_generate_messages_cpp) + +add_executable(bio_main5 src/bio_main5.cpp) +target_link_libraries(bio_main5 ${catkin_LIBRARIES} follower_lib Leader_lib /home/dodo/ardupilot_ws/src/class_model/libs/libyaml-cpp.a) +add_dependencies(bio_main5 class_model_generate_messages_cpp) ################json test add_executable(json src/json.cpp) diff --git a/class_model/include/class_model/follower.h b/class_model/include/class_model/follower.h index 27fe4ad..fcb77a7 100755 --- a/class_model/include/class_model/follower.h +++ b/class_model/include/class_model/follower.h @@ -31,6 +31,8 @@ public: DroneStatus drone1; DroneStatus drone2; DroneStatus drone3; + DroneStatus drone4; + DroneStatus drone5; DroneStatus self; DroneStatus samePlane[5]; @@ -56,7 +58,7 @@ private: float distance = config["formation"]["distance"].as(); float angle = config["formation"]["angle"].as(); float error_lon,error_lat; - float follower_pid[3] = {1 , 0.00000000001 ,0.5}; + float follower_pid[3] = {1 , 0.00000000001 ,0};// D downsize float ignore_small = 0.50; void calculate_position(float k,float theta,int plane); diff --git a/class_model/include/class_model/formation.h b/class_model/include/class_model/formation.h index 3e647a9..b8665de 100755 --- a/class_model/include/class_model/formation.h +++ b/class_model/include/class_model/formation.h @@ -37,6 +37,7 @@ public: void follower3(int type); void follower4(int type); void follower5(int type); + void follower6(int type); void sph_follower1(int type); void sph_follower2(int type); void sph_follower3(int type); @@ -54,8 +55,8 @@ private: int flag = 0,heading_status = 0,buf = 0; float pre_alt,cur_alt; float error_lon,error_lat; - float leader_pid[3] = {1 , 0.000000000001 ,0.5}; - float follower_pid[3] = {1 , 0.00000000001 ,0.5}; + float leader_pid[3] = {1 , 0.000000000001 ,0}; + float follower_pid[3] = {1 , 0.00000000001 ,0}; float ignore_small = 0.50; void calculate_position(float k,float theta,int direction=0); diff --git a/class_model/include/class_model/requestData.h b/class_model/include/class_model/requestData.h index 41d16d0..713162c 100755 --- a/class_model/include/class_model/requestData.h +++ b/class_model/include/class_model/requestData.h @@ -25,6 +25,8 @@ public: global_location get_self_GPS(); global_location get_M1_GPS(); global_location get_M2_GPS(); + global_location get_M3_GPS(); + global_location get_M4_GPS(); float get_leader_heading(); int get_formation_message(); json get_data(); @@ -37,16 +39,18 @@ private: void drone1_callback(const std_msgs::String::ConstPtr &gps); void drone2_callback(const std_msgs::String::ConstPtr &gps); void drone3_callback(const std_msgs::String::ConstPtr &gps); + void drone4_callback(const std_msgs::String::ConstPtr &gps); + void drone5_callback(const std_msgs::String::ConstPtr &gps); void Message_callback(const std_msgs::String::ConstPtr &message); void jsonToString(std::string data); void L_INFO(std::string data); void Bio_INFO(json json_data,int drone_ID); float heading; global_location leader_position; - global_location self_position,M1_position,M2_position; - std::array ID_array {1,2,3}; + global_location self_position,M1_position,M2_position,M3_position,M4_position; + std::array ID_array {1,2,3,4,5}; // rapidjson::Document document; - json j_data,j_data2,j_data3; + json j_data,j_data2,j_data3,j_data4,j_data5; int self_ID,drone_ID; // SUBSCRIBE @@ -55,6 +59,8 @@ private: ros::Subscriber drone1_data; ros::Subscriber drone2_data; ros::Subscriber drone3_data; + ros::Subscriber drone4_data; + ros::Subscriber drone5_data; }; #endif // REQUESTDATA_H diff --git a/class_model/include/class_model/select.h b/class_model/include/class_model/select.h index 749add0..6b34893 100755 --- a/class_model/include/class_model/select.h +++ b/class_model/include/class_model/select.h @@ -22,6 +22,7 @@ public: void goose_formation(float x=0,float y=0); void protect_formation(float x=0,float y=0); void Hex_formation(float x=0,float y=0); + void house_formation(float x=0,float y=0); void start_formation(); void stop(); diff --git a/class_model/launch/mqtt_old.launch b/class_model/launch/mqtt_old.launch index 9f718b2..f078a75 100755 --- a/class_model/launch/mqtt_old.launch +++ b/class_model/launch/mqtt_old.launch @@ -11,7 +11,7 @@ - + diff --git a/class_model/src/PID.cpp b/class_model/src/PID.cpp index a8eb07d..a8267fa 100755 --- a/class_model/src/PID.cpp +++ b/class_model/src/PID.cpp @@ -12,7 +12,7 @@ float PIDClass::update(float current ,float target ,float pidvals[3]){ current_time = std::clock(); // pTime = current_time - double t = (current_time - pTime); - float error = (target - current)/1.1; + float error = (target - current); double P,D,result; P = pidvals[0] * error; diff --git a/class_model/src/bio_main.cpp b/class_model/src/bio_main.cpp index a7f5f70..4613a87 100644 --- a/class_model/src/bio_main.cpp +++ b/class_model/src/bio_main.cpp @@ -21,7 +21,7 @@ int main(int argc, char **argv) { // SelectionClass selection_object; - global_location target,self,M1,M2; + global_location target,self,M1,M2,M3,M4; int ref_ID,checkLeader; YAML::Node config = YAML::LoadFile("/home/dodo/ardupilot_ws/src/class_model/src/config.yaml"); //reading yaml parameter(target point) @@ -32,9 +32,13 @@ int main(int argc, char **argv) { self = request_object.get_self_GPS(); M1 = request_object.get_M1_GPS(); M2 = request_object.get_M2_GPS(); + M3 = request_object.get_M3_GPS(); + M4 = request_object.get_M4_GPS(); - global_location pos[] = {target,self,M1,M2}; - global_location member[] = {M1,M2}; + // global_location pos[] = {target,self,M1,M2}; + // global_location member[] = {M1,M2}; + global_location pos[] = {target,self,M1,M2,M3,M4}; + global_location member[] = {M1,M2,M3,M4}; size_t index = sizeof(pos)/sizeof(pos[0]); size_t m_index = sizeof(member)/sizeof(member[0]); diff --git a/class_model/src/bio_main2.cpp b/class_model/src/bio_main2.cpp index dabc7f7..e05ce83 100644 --- a/class_model/src/bio_main2.cpp +++ b/class_model/src/bio_main2.cpp @@ -21,10 +21,10 @@ int main(int argc, char **argv) { // SelectionClass selection_object; - global_location target,self,M1,M2; + global_location target,self,M1,M2,M3,M4; int ref_ID,checkLeader; - YAML::Node config = YAML::LoadFile("/home/dodo/ardupilot_ws/src/class_model/src/config2.yaml"); //reading yaml parameter(target point) + YAML::Node config = YAML::LoadFile("/home/dodo/ardupilot_ws/src/class_model/src/config.yaml"); //reading yaml parameter(target point) target.lon = config["routh1"]["x"].as()*1e7; target.lat = config["routh1"]["y"].as()*1e7; @@ -32,11 +32,13 @@ int main(int argc, char **argv) { self = request_object.get_self_GPS(); M1 = request_object.get_M1_GPS(); M2 = request_object.get_M2_GPS(); + M3 = request_object.get_M3_GPS(); + M4 = request_object.get_M4_GPS(); - std::cout <()*1e7; target.lat = config["routh1"]["y"].as()*1e7; @@ -32,9 +32,13 @@ int main(int argc, char **argv) { self = request_object.get_self_GPS(); M1 = request_object.get_M1_GPS(); M2 = request_object.get_M2_GPS(); + M3 = request_object.get_M3_GPS(); + M4 = request_object.get_M4_GPS(); - global_location pos[] = {target,self,M1,M2}; - global_location member[] = {M1,M2}; + // global_location pos[] = {target,self,M1,M2}; + // global_location member[] = {M1,M2}; + global_location pos[] = {target,self,M1,M2,M3,M4}; + global_location member[] = {M1,M2,M3,M4}; size_t index = sizeof(pos)/sizeof(pos[0]); size_t m_index = sizeof(member)/sizeof(member[0]); diff --git a/class_model/src/bio_main4.cpp b/class_model/src/bio_main4.cpp new file mode 100644 index 0000000..de85900 --- /dev/null +++ b/class_model/src/bio_main4.cpp @@ -0,0 +1,66 @@ +#include "class_model/FindLeader.h" +#include "class_model/Leader.h" +#include "class_model/follower.h" +#include "yaml-cpp/yaml.h" + +int main(int argc, char **argv) { + + // Init ROS node + ros::init(argc, argv, "drone4_node"); + + // reate Assync spiner + ros::AsyncSpinner spinner(0); + spinner.start(); + // ros::Rate rate(5); + + ModeClass mode_object; + ControlClass control_object; + RequestClass request_object; + FollowerClass follower_object; + LeaderClass leader_object; + + // SelectionClass selection_object; + + global_location target,self,M1,M2,M3,M4; + int ref_ID,checkLeader; + + YAML::Node config = YAML::LoadFile("/home/dodo/ardupilot_ws/src/class_model/src/config.yaml"); //reading yaml parameter(target point) + target.lon = config["routh1"]["x"].as()*1e7; + target.lat = config["routh1"]["y"].as()*1e7; + + sleep(5); + self = request_object.get_self_GPS(); + M1 = request_object.get_M1_GPS(); + M2 = request_object.get_M2_GPS(); + M3 = request_object.get_M3_GPS(); + M4 = request_object.get_M4_GPS(); + + // global_location pos[] = {target,self,M1,M2}; + // global_location member[] = {M1,M2}; + global_location pos[] = {target,self,M1,M2,M3,M4}; + global_location member[] = {M1,M2,M3,M4}; + size_t index = sizeof(pos)/sizeof(pos[0]); + size_t m_index = sizeof(member)/sizeof(member[0]); + + mode_object.set_Mode("GUIDED"); + control_object.arm(); + control_object.takeoff(2); + + checkLeader = check_leader(pos,index).is_leader; + if(checkLeader != 1){ + ref_ID = follower_object.find_ref_drone(pos,index,check_leader(pos,index).leader_ID); //find_ref_drone(pos,index,leader_ID); + } + + while(true){ + + if(checkLeader == 1){ + // leader_object.leader(target); + }else{ + follower_object.follower(member,m_index,ref_ID); //follow reference drone position + } + } + ros::waitForShutdown(); + + return 0; + +} \ No newline at end of file diff --git a/class_model/src/bio_main5.cpp b/class_model/src/bio_main5.cpp new file mode 100644 index 0000000..d1daa95 --- /dev/null +++ b/class_model/src/bio_main5.cpp @@ -0,0 +1,66 @@ +#include "class_model/FindLeader.h" +#include "class_model/Leader.h" +#include "class_model/follower.h" +#include "yaml-cpp/yaml.h" + +int main(int argc, char **argv) { + + // Init ROS node + ros::init(argc, argv, "drone5_node"); + + // reate Assync spiner + ros::AsyncSpinner spinner(0); + spinner.start(); + // ros::Rate rate(5); + + ModeClass mode_object; + ControlClass control_object; + RequestClass request_object; + FollowerClass follower_object; + LeaderClass leader_object; + + // SelectionClass selection_object; + + global_location target,self,M1,M2,M3,M4; + int ref_ID,checkLeader; + + YAML::Node config = YAML::LoadFile("/home/dodo/ardupilot_ws/src/class_model/src/config.yaml"); //reading yaml parameter(target point) + target.lon = config["routh1"]["x"].as()*1e7; + target.lat = config["routh1"]["y"].as()*1e7; + + sleep(5); + self = request_object.get_self_GPS(); + M1 = request_object.get_M1_GPS(); + M2 = request_object.get_M2_GPS(); + M3 = request_object.get_M3_GPS(); + M4 = request_object.get_M4_GPS(); + + // global_location pos[] = {target,self,M1,M2}; + // global_location member[] = {M1,M2}; + global_location pos[] = {target,self,M1,M2,M3,M4}; + global_location member[] = {M1,M2,M3,M4}; + size_t index = sizeof(pos)/sizeof(pos[0]); + size_t m_index = sizeof(member)/sizeof(member[0]); + + mode_object.set_Mode("GUIDED"); + control_object.arm(); + control_object.takeoff(2); + + checkLeader = check_leader(pos,index).is_leader; + if(checkLeader != 1){ + ref_ID = follower_object.find_ref_drone(pos,index,check_leader(pos,index).leader_ID); //find_ref_drone(pos,index,leader_ID); + } + + while(true){ + + if(checkLeader == 1){ + // leader_object.leader(target); + }else{ + follower_object.follower(member,m_index,ref_ID); //follow reference drone position + } + } + ros::waitForShutdown(); + + return 0; + +} \ No newline at end of file diff --git a/class_model/src/command.py b/class_model/src/command.py index 7bc88f7..1efac16 100755 --- a/class_model/src/command.py +++ b/class_model/src/command.py @@ -18,6 +18,7 @@ def ros_pub(dataJson): publisher3.publish(dataJson) publisher4.publish(dataJson) publisher5.publish(dataJson) + publisher6.publish(dataJson) rate.sleep() # print(f"publish data {data}") @@ -71,6 +72,9 @@ if __name__ == '__main__': topicName5 = '/drone5/cmd_receiver' publisher5 = rospy.Publisher(topicName5,String,queue_size=10) + topicName6 = '/drone6/cmd_receiver' + publisher6 = rospy.Publisher(topicName6,String,queue_size=10) + rate = rospy.Rate(10) diff --git a/class_model/src/follower.cpp b/class_model/src/follower.cpp index 9f2c7ed..ef34269 100755 --- a/class_model/src/follower.cpp +++ b/class_model/src/follower.cpp @@ -19,6 +19,12 @@ void FollowerClass::follower(global_location* member_data, size_t index, int ref }else if (refID == member_data[1].ID) { ref = &RequestClass::get_M2_GPS; + }else if (refID == member_data[2].ID) + { + ref = &RequestClass::get_M3_GPS; + }else if (refID == member_data[3].ID) + { + ref = &RequestClass::get_M4_GPS; } std::string command = ""; @@ -66,7 +72,19 @@ void FollowerClass::plane(global_location target, global_location leader, global drone3.init_location.lon = follower.lon; drone3.ID = follower.ID; drone3.plane = 1; + break; + case 4: + drone4.init_location.lat = follower.lat; + drone4.init_location.lon = follower.lon; + drone4.ID = follower.ID; + drone4.plane = 1; break; + case 5: + drone5.init_location.lat = follower.lat; + drone5.init_location.lon = follower.lon; + drone5.ID = follower.ID; + drone5.plane = 1; + break; } }else if(follower.lat > y){ // std::cout<< follower.lat <<","<< y <data); Bio_INFO(j_data3,drone_ID); } +void RequestClass::drone4_callback(const std_msgs::String::ConstPtr &sensor) { + drone_ID = 4; + j_data4 = json::parse(sensor->data); + Bio_INFO(j_data4,drone_ID); +} +void RequestClass::drone5_callback(const std_msgs::String::ConstPtr &sensor) { + drone_ID = 5; + j_data5 = json::parse(sensor->data); + Bio_INFO(j_data5,drone_ID); +} void RequestClass::Bio_INFO(json json_data,int drone_ID){ @@ -146,6 +161,18 @@ void RequestClass::Bio_INFO(json json_data,int drone_ID){ // M2_position.alt = std::stoi(json_data["alt"].get()); M2_position.heading = json_data["heading"]; M2_position.ID = drone_ID; + }else if (drone_ID == ID_array[2]){ + M3_position.lat = json_data["lat"]; + M3_position.lon = json_data["lon"]; + // M2_position.alt = std::stoi(json_data["alt"].get()); + M3_position.heading = json_data["heading"]; + M3_position.ID = drone_ID; + }else if (drone_ID == ID_array[3]){ + M4_position.lat = json_data["lat"]; + M4_position.lon = json_data["lon"]; + // M2_position.alt = std::stoi(json_data["alt"].get()); + M4_position.heading = json_data["heading"]; + M4_position.ID = drone_ID; } } @@ -159,4 +186,12 @@ global_location RequestClass::get_M1_GPS(){ global_location RequestClass::get_M2_GPS(){ return M2_position; +} +global_location RequestClass::get_M3_GPS(){ + + return M3_position; +} +global_location RequestClass::get_M4_GPS(){ + + return M4_position; } \ No newline at end of file diff --git a/class_model/src/select.cpp b/class_model/src/select.cpp index c498f5e..bd80b60 100755 --- a/class_model/src/select.cpp +++ b/class_model/src/select.cpp @@ -57,6 +57,8 @@ void SelectClass::goose_formation(float x ,float y){ formation_object.follower4(counter); }else if(param_object.getID() == 6){ formation_object.follower5(counter); + }else if(param_object.getID() == 7){ + formation_object.follower6(counter); } @@ -81,6 +83,8 @@ void SelectClass::line_formation(float x ,float y){ formation_object.follower4(counter); }else if(param_object.getID() == 6){ formation_object.follower5(counter); + }else if(param_object.getID() == 7){ + formation_object.follower6(counter); } // sleep(2); @@ -103,6 +107,8 @@ void SelectClass::row_formation(float x ,float y){ formation_object.follower4(counter); }else if(param_object.getID() == 6){ formation_object.follower5(counter); + }else if(param_object.getID() == 7){ + formation_object.follower6(counter); } // sleep(2); @@ -191,6 +197,32 @@ void SelectClass::start_formation(){ } } +void SelectClass::house_formation(float x ,float y){ + + counter = 6; + if(param_object.getID() == 1){ + formation_object.leader1(x,y); + }else if(param_object.getID() == 2){ + formation_object.follower1(counter); + }else if(param_object.getID() == 3){ + formation_object.follower2(counter); + }else if(param_object.getID() == 4){ + formation_object.follower3(counter); + }else if(param_object.getID() == 5){ + formation_object.follower4(counter); + }else if(param_object.getID() == 6){ + formation_object.follower5(counter); + }else if(param_object.getID() == 7){ + formation_object.follower6(counter); + } + + + // sleep(2); + + // mode_object.set_Mode("LAND"); + +} + void SelectClass::stop(){ } \ No newline at end of file diff --git a/class_model/src/utils/mqttConfig_PUB4.yml b/class_model/src/utils/mqttConfig_PUB4.yml new file mode 100644 index 0000000..6f2152c --- /dev/null +++ b/class_model/src/utils/mqttConfig_PUB4.yml @@ -0,0 +1,22 @@ +MQTT: + msg_format: Json + MQTTClientNamePub: Drone888Pub + host: 140.120.31.133 + port: 1883 + keepalive: 60 + willTopic: CheckDoneConnect + willTopicQOS: 1 + lwt: Drone888 Gone Offline + willRetain: False + # Mqtt topic + Flight_Information_topicToMqtt: Drone888/Flight_Information + Fly_Formation_topicToMqtt: Drone888/Formation + # Change formate qos + Fly_Formation_topicToMqtt_QOS: 2 + #ROS +ROS: + ROSClientNamePub: Drone888Pub + ROStopicName_Flight_Information: Drone888_Flight_Information_reciver + ROStopicName_Fly_Formation: Fly_Formation_reciver +LOG: + logFileName: pub.log diff --git a/class_model/src/utils/mqttConfig_PUB5.yml b/class_model/src/utils/mqttConfig_PUB5.yml new file mode 100644 index 0000000..5735165 --- /dev/null +++ b/class_model/src/utils/mqttConfig_PUB5.yml @@ -0,0 +1,22 @@ +MQTT: + msg_format: Json + MQTTClientNamePub: Drone555Pub + host: 140.120.31.133 + port: 1883 + keepalive: 60 + willTopic: CheckDoneConnect + willTopicQOS: 1 + lwt: Drone555 Gone Offline + willRetain: False + # Mqtt topic + Flight_Information_topicToMqtt: Drone555/Flight_Information + Fly_Formation_topicToMqtt: Drone555/Formation + # Change formate qos + Fly_Formation_topicToMqtt_QOS: 2 + #ROS +ROS: + ROSClientNamePub: Drone555Pub + ROStopicName_Flight_Information: Drone555_Flight_Information_reciver + ROStopicName_Fly_Formation: Fly_Formation_reciver +LOG: + logFileName: pub.log diff --git a/class_model/src/utils/mqttConfig_SUB.yml b/class_model/src/utils/mqttConfig_SUB.yml index 8e6adc7..2d4ef73 100644 --- a/class_model/src/utils/mqttConfig_SUB.yml +++ b/class_model/src/utils/mqttConfig_SUB.yml @@ -16,6 +16,10 @@ MQTT: Drone650_Flight_Information_topicToMqtt: Drone650/Flight_Information + Drone888_Flight_Information_topicToMqtt: Drone888/Flight_Information + + Drone555_Flight_Information_topicToMqtt: Drone555/Flight_Information + # Change formate qos Fly_Formation_topicToMqtt_QOS: 2 ROS: @@ -26,5 +30,8 @@ ROS: Dron380_ROStopicName_Flight_Information: Dron380_Flight_Information_reciver Dron650_ROStopicName_Flight_Information: Dron650_Flight_Information_reciver + + Dron888_ROStopicName_Flight_Information: Dron888_Flight_Information_reciver + Dron555_ROStopicName_Flight_Information: Dron555_Flight_Information_reciver LOG: logFileName: sub.log diff --git a/class_model/src/utils/mqttConfig_SUB2.yml b/class_model/src/utils/mqttConfig_SUB2.yml index dd3984c..cbc5c8c 100644 --- a/class_model/src/utils/mqttConfig_SUB2.yml +++ b/class_model/src/utils/mqttConfig_SUB2.yml @@ -6,7 +6,7 @@ MQTT: keepalive: 60 willTopic: CheckDoneConnect willTopicQOS: 1 - lwt: Dron550 Gone Offline + lwt: Dron650 Gone Offline willRetain: False # Mqtt topic Fly_Formation_topicToMqtt: Drone650/Formation @@ -16,6 +16,10 @@ MQTT: Drone650_Flight_Information_topicToMqtt: Drone650/Flight_Information + Drone888_Flight_Information_topicToMqtt: Drone888/Flight_Information + + Drone555_Flight_Information_topicToMqtt: Drone555/Flight_Information + # Change formate qos Fly_Formation_topicToMqtt_QOS: 2 ROS: @@ -26,5 +30,8 @@ ROS: Dron380_ROStopicName_Flight_Information: Dron380_Flight_Information_reciver Dron650_ROStopicName_Flight_Information: Dron650_Flight_Information_reciver + + Dron888_ROStopicName_Flight_Information: Dron888_Flight_Information_reciver + Dron555_ROStopicName_Flight_Information: Dron555_Flight_Information_reciver LOG: logFileName: sub.log diff --git a/class_model/src/utils/mqttConfig_SUB3.yml b/class_model/src/utils/mqttConfig_SUB3.yml index 5398262..0e08679 100644 --- a/class_model/src/utils/mqttConfig_SUB3.yml +++ b/class_model/src/utils/mqttConfig_SUB3.yml @@ -6,7 +6,7 @@ MQTT: keepalive: 60 willTopic: CheckDoneConnect willTopicQOS: 1 - lwt: Dron550 Gone Offline + lwt: Dron380 Gone Offline willRetain: False # Mqtt topic Fly_Formation_topicToMqtt: Drone380/Formation @@ -16,6 +16,9 @@ MQTT: Drone650_Flight_Information_topicToMqtt: Drone650/Flight_Information + Drone888_Flight_Information_topicToMqtt: Drone888/Flight_Information + Drone555_Flight_Information_topicToMqtt: Drone555/Flight_Information + # Change formate qos Fly_Formation_topicToMqtt_QOS: 2 ROS: @@ -26,5 +29,8 @@ ROS: Dron380_ROStopicName_Flight_Information: Dron380_Flight_Information_reciver Dron650_ROStopicName_Flight_Information: Dron650_Flight_Information_reciver + + Dron888_ROStopicName_Flight_Information: Dron888_Flight_Information_reciver + Dron555_ROStopicName_Flight_Information: Dron555_Flight_Information_reciver LOG: logFileName: sub.log diff --git a/class_model/src/utils/mqttConfig_SUB4.yml b/class_model/src/utils/mqttConfig_SUB4.yml new file mode 100644 index 0000000..dd2e9eb --- /dev/null +++ b/class_model/src/utils/mqttConfig_SUB4.yml @@ -0,0 +1,38 @@ +MQTT: + msg_format: Json + MQTTClientNameSub: Drone888Sub + host: 140.120.31.133 + port: 1883 + keepalive: 60 + willTopic: CheckDoneConnect + willTopicQOS: 1 + lwt: Drone888 Gone Offline + willRetain: False + # Mqtt topic + Fly_Formation_topicToMqtt: Drone888/Formation + Drone550_Flight_Information_topicToMqtt: Drone550/Flight_Information + + Drone380_Flight_Information_topicToMqtt: Drone380/Flight_Information + + Drone650_Flight_Information_topicToMqtt: Drone650/Flight_Information + + Drone888_Flight_Information_topicToMqtt: Drone888/Flight_Information + + Drone555_Flight_Information_topicToMqtt: Drone555/Flight_Information + + # Change formate qos + Fly_Formation_topicToMqtt_QOS: 2 +ROS: + ROSClientNameSub: Drone888Sub + ROStopicName_Fly_Formation: Fly_Formation_reciver + Dron550_ROStopicName_Flight_Information: Dron550_Flight_Information_reciver + + Dron380_ROStopicName_Flight_Information: Dron380_Flight_Information_reciver + + Dron650_ROStopicName_Flight_Information: Dron650_Flight_Information_reciver + + Dron888_ROStopicName_Flight_Information: Dron888_Flight_Information_reciver + + Dron555_ROStopicName_Flight_Information: Dron555_Flight_Information_reciver +LOG: + logFileName: sub.log diff --git a/class_model/src/utils/mqttConfig_SUB5.yml b/class_model/src/utils/mqttConfig_SUB5.yml new file mode 100644 index 0000000..40c10ce --- /dev/null +++ b/class_model/src/utils/mqttConfig_SUB5.yml @@ -0,0 +1,38 @@ +MQTT: + msg_format: Json + MQTTClientNameSub: Drone555Sub + host: 140.120.31.133 + port: 1883 + keepalive: 60 + willTopic: CheckDoneConnect + willTopicQOS: 1 + lwt: Drone555 Gone Offline + willRetain: False + # Mqtt topic + Fly_Formation_topicToMqtt: Drone555/Formation + Drone550_Flight_Information_topicToMqtt: Drone550/Flight_Information + + Drone380_Flight_Information_topicToMqtt: Drone380/Flight_Information + + Drone650_Flight_Information_topicToMqtt: Drone650/Flight_Information + + Drone888_Flight_Information_topicToMqtt: Drone888/Flight_Information + + Drone555_Flight_Information_topicToMqtt: Drone555/Flight_Information + + # Change formate qos + Fly_Formation_topicToMqtt_QOS: 2 +ROS: + ROSClientNameSub: Drone555Sub + ROStopicName_Fly_Formation: Fly_Formation_reciver + Dron550_ROStopicName_Flight_Information: Dron550_Flight_Information_reciver + + Dron380_ROStopicName_Flight_Information: Dron380_Flight_Information_reciver + + Dron650_ROStopicName_Flight_Information: Dron650_Flight_Information_reciver + + Dron888_ROStopicName_Flight_Information: Dron888_Flight_Information_reciver + + Dron555_ROStopicName_Flight_Information: Dron555_Flight_Information_reciver +LOG: + logFileName: sub.log diff --git a/class_model/src/utils/protoJson_mqtt_pub_data_to_ros.py b/class_model/src/utils/protoJson_mqtt_pub_data_to_ros.py index 13bea22..92ce87a 100644 --- a/class_model/src/utils/protoJson_mqtt_pub_data_to_ros.py +++ b/class_model/src/utils/protoJson_mqtt_pub_data_to_ros.py @@ -41,6 +41,8 @@ class Json_msg_to_ros: Drone550_publisher_Flight_Information = None Drone380_publisher_Flight_Information = None Drone650_publisher_Flight_Information = None + Drone888_publisher_Flight_Information = None + Drone555_publisher_Flight_Information = None #Mqtt topic: check data from which topic @@ -76,4 +78,22 @@ class Json_msg_to_ros: cls.rate.sleep() t = threading.Thread(target=thread_function) - t.start() + t.start() + + @classmethod + def Drone888_on_message_Flight_Information(cls, client, userdata, msg): + def thread_function(): + cls.Drone888_publisher_Flight_Information.publish(msg.payload.decode("UTF-8")) + cls.rate.sleep() + + t = threading.Thread(target=thread_function) + t.start() + + @classmethod + def Drone555_on_message_Flight_Information(cls, client, userdata, msg): + def thread_function(): + cls.Drone555_publisher_Flight_Information.publish(msg.payload.decode("UTF-8")) + cls.rate.sleep() + + t = threading.Thread(target=thread_function) + t.start() \ No newline at end of file diff --git a/class_model/src/utils/protoJson_mqtt_sub_data_from_ros.py b/class_model/src/utils/protoJson_mqtt_sub_data_from_ros.py index 8602d41..97411b1 100644 --- a/class_model/src/utils/protoJson_mqtt_sub_data_from_ros.py +++ b/class_model/src/utils/protoJson_mqtt_sub_data_from_ros.py @@ -78,8 +78,7 @@ class Json_msg_from_ros: alt=int(GPS.altitude*100) dataGpsUpdate = {"lat": lat, "lon": lon, "alt": alt} cls.GPS_Data.update(dataGpsUpdate) - dataJsonFormate = orjson.dumps(cls.GPS_Data) - cls.mqtt_Pub(message=dataJsonFormate, topics=cls.Flight_Information_topicToMqtt) + # TODO: does decode need utf8 @@ -90,6 +89,7 @@ class Json_msg_from_ros: cls.GPS_Data.update(dataGpsUpdate) dataJsonFormate = orjson.dumps(cls.GPS_Data) cls.mqtt_Pub(message=dataJsonFormate, topics=cls.Flight_Information_topicToMqtt) + @classmethod def callBack_fly_formation(cls, Formation): Formation_data = {"velocity": Formation.velocity, "type": Formation.type} diff --git a/class_model/src/utils/readConfig.py b/class_model/src/utils/readConfig.py index 65ca5e7..03bb330 100644 --- a/class_model/src/utils/readConfig.py +++ b/class_model/src/utils/readConfig.py @@ -86,6 +86,8 @@ class Read_SUB_Config(Config): "Drone550_Flight_Information_topicToMqtt": (str,False), "Drone380_Flight_Information_topicToMqtt":(str,False), "Drone650_Flight_Information_topicToMqtt":(str,False), + "Drone888_Flight_Information_topicToMqtt":(str,False), + "Drone555_Flight_Information_topicToMqtt":(str,False), "Fly_Formation_topicToMqtt": (str,False), "Fly_Formation_topicToMqtt_QOS":(int,False)}, self.sectionNames[1]:{ @@ -94,6 +96,9 @@ class Read_SUB_Config(Config): "Dron380_ROStopicName_Flight_Information": (str,False), "Dron380_ROStopicName_Flight_Information": (str,False), "Dron650_ROStopicName_Flight_Information": (str,False), + "Dron888_ROStopicName_Flight_Information": (str,False), + "Dron555_ROStopicName_Flight_Information": (str,False), + "Dron_ROStopicName_Flight_Information": (str,False), "ROStopicName_Fly_Formation": (str,False)}, self.sectionNames[2]:{ "logFileName":(str,False)}} diff --git a/iq_sim/launch/multi_drone.launch b/iq_sim/launch/multi_drone.launch deleted file mode 100644 index 5dad88b..0000000 --- a/iq_sim/launch/multi_drone.launch +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - \ No newline at end of file diff --git a/iq_sim/worlds/multi_drone.world b/iq_sim/worlds/five_drone.world similarity index 96% rename from iq_sim/worlds/multi_drone.world rename to iq_sim/worlds/five_drone.world index 4a4cc9f..1921470 100644 --- a/iq_sim/worlds/multi_drone.world +++ b/iq_sim/worlds/five_drone.world @@ -117,32 +117,32 @@ - -10 -10 0 0 0 0 + 0 0 0 0 0 0 model://drone_with_camera - -10 -12 0 0 0 0 + 0 4 0 0 0 0 model://drone2 - -10 -8 0 0 0 0 + 0 8 0 0 0 0 model://drone3 - -10 -14 0 0 0 0 + 0 -4 0 0 0 0 model://drone4 - -10 -6 0 0 0 0 + 0 -8 0 0 0 0 model://drone5