23 m_tgt_pub =
_nh.advertise<common_msgs::target>(
"/nndp_cpp/tgt", 1);
26 _nh.advertise<common_msgs::state>(
"/task_manager/current_state", 1);
28 m_swarm_pub =
_nh.advertise<std_msgs::Bool>(
"/task_manager/swarm", 1);
31 _nh.advertise<std_msgs::Byte>(
"/task_manager/error_state", 1);
34 "/task_manager/mpc_init_position_nwu", 1);
36 "/task_manager/position_nwu", 1);
39 "/mavros/setpoint_raw/local", 10);
82 std::cout <<
"_simulation: " <<
_simulation << std::endl;
90 std::cout <<
"yaw_control: " <<
yaw_control_ << std::endl;
95 _nh.serviceClient<mavros_msgs::CommandHome>(
"/mavros/cmd/set_home");
97 _nh.serviceClient<mavros_msgs::CommandTOL>(
"/mavros/cmd/land");
99 _nh.serviceClient<mavros_msgs::CommandBool>(
"/mavros/cmd/arming");
101 _nh.serviceClient<mavros_msgs::SetMode>(
"/mavros/set_mode");
107 ROS_INFO(
"Task manager is ready!");
116 const geometry_msgs::PoseStamped::ConstPtr &msg)
120 geometry_msgs::PoseStamped pos_nwu;
129 common_msgs::target tgt;
130 tgt.controller = controlMode;
138 float tgtZ,
float yaw)
140 common_msgs::target tgt;
141 tgt.controller = controlMode;
151 common_msgs::target tgt = *msg;
157 common_msgs::target tgt = *msg;
165 geometry_msgs::Point deltaP;
170 tgt.tgt.x =
m_uav_pose.pose.position.y + deltaP.x;
171 tgt.tgt.y = -
m_uav_pose.pose.position.x + deltaP.y;
172 tgt.tgt.z =
m_uav_pose.pose.position.z + deltaP.z;
191 geometry_msgs::Point deltP;
208 ROS_INFO(
"Shut down swarm Algo.");
216 ROS_WARN(
"APPROACH");
218 ROS_INFO(
"Flying 15m to south.");
233 ROS_INFO(
"Landing triggered by offline status.");
262 ROS_INFO(
"Got command from web GCS");
282 ROS_INFO(
"UAV is taking off!");
291 ROS_INFO(
"Mission starts!");
298 ROS_ERROR(
"Mission Load failed!");
303 ROS_ERROR(
"Please send takeoff command first!");
311 ROS_INFO_STREAM(
"Switch from " <<
mUavTaskState <<
"to SWARM");
337 ROS_ERROR(
"Please send takeoff command first!");
358 ROS_WARN(
"DDrone: LAND");
369 ROS_INFO(
"Initialize Setpoints...");
371 ros::Rate rate(20.0);
372 ros::Time last_request = ros::Time::now();
378 if (ros::Time::now() - last_request > ros::Duration(5.0))
380 ROS_ERROR(
"FCU not connect for 5s. Stop takeoff procedure.");
384 ROS_INFO(
"FCU Connected");
386 mavros_msgs::PositionTarget init_sp;
387 init_sp.coordinate_frame = mavros_msgs::PositionTarget::FRAME_LOCAL_NED;
388 init_sp.position.x =
m_uav_pose.pose.position.x;
389 init_sp.position.y =
m_uav_pose.pose.position.y;
390 init_sp.position.z =
m_uav_pose.pose.position.z;
391 init_sp.velocity.x = 0;
392 init_sp.velocity.y = 0;
393 init_sp.velocity.z = 0;
394 init_sp.acceleration_or_force.x = 0;
395 init_sp.acceleration_or_force.y = 0;
396 init_sp.acceleration_or_force.z = 0;
406 geometry_msgs::PoseStamped mpc_init_pos;
410 for (
int i = 10; ros::ok() && i > 0; --i)
416 mavros_msgs::SetMode offb_set_mode;
417 offb_set_mode.request.custom_mode =
"OFFBOARD";
419 mavros_msgs::CommandBool arm_cmd;
420 arm_cmd.request.value =
true;
422 bool is_mode_ready =
false;
423 bool is_armed =
false;
424 last_request = ros::Time::now();
428 is_mode_ready =
true;
432 while (!(is_mode_ready && is_armed))
435 (ros::Time::now() - last_request > ros::Duration(1.0)))
437 ROS_INFO(
"try set offboard");
439 offb_set_mode.response.mode_sent)
441 ROS_INFO(
"Offboard enabled");
443 last_request = ros::Time::now();
448 (ros::Time::now() - last_request > ros::Duration(1.0)))
453 ROS_INFO(
"Vehicle armed");
455 last_request = ros::Time::now();
477 mavros_msgs::CommandTOL land_cmd;
478 land_cmd.request.yaw = 0;
479 land_cmd.request.latitude = 0;
480 land_cmd.request.longitude = 0;
481 land_cmd.request.altitude = 0;
485 if (land_cmd.response.success)
487 ROS_INFO(
"land command succeed");
492 ROS_ERROR(
"LAND Command Failed!");
511 std_srvs::Trigger srv;
523 ROS_ERROR(
"Failed to activate engine0");
528 mavros_msgs::CommandHome mavros_set_home_srv;
529 mavros_set_home_srv.request.current_gps =
true;
532 if (mavros_set_home_srv.response.success)
534 std::string info_string(
" Set home succeed!");
535 ROS_INFO_STREAM(info_string);
539 std::string info_string(
" Set home failed!");
540 ROS_INFO_STREAM(info_string);
545 std::string info_string(
" Failed to call service "
547 ROS_INFO_STREAM(info_string);
557 ROS_INFO(
"Got polygon with %d points",
int(
m_ui_points.points.size()));
563 ROS_INFO(
"Skip current point!");
574 double roll, pitch, yaw;
575 m.getRPY(roll, pitch, yaw);
578 ROS_INFO(
"Initialized yaw value %f: ", yaw);
584 tf::Matrix3x3 R_enu2nwu;
585 R_enu2nwu.setRPY(0.0, 0.0, -3.1415926 / 2);
586 tf::Matrix3x3 R_nwu = R_enu2nwu * m;
588 R_nwu.getRPY(roll, pitch, yaw_nwu);
613 ROS_INFO(
"Clear Mission");
622 bool succeed =
false;
626 ROS_INFO(
"Loading from local waypoints file");
628 while (std::getline(infile, line))
630 std::istringstream iss(line);
632 if (!(iss >> _1 >> _2 >> _3))
634 ROS_ERROR(
"The data size is not correct!");
638 geometry_msgs::Point p;
646 ROS_INFO(
"Goto wp: 0");
658 ROS_INFO(
"Points have been loaded!");
724 ROS_INFO(
"Loading from velocity points from file");
725 while (std::getline(infile, line))
727 std::istringstream iss(line);
728 double _1, _2, _3, _4;
729 if (!(iss >> _1 >> _2 >> _3 >> _4))
731 ROS_ERROR(
"The data size is not correct!");
735 geometry_msgs::Point p;
741 ROS_INFO(
"Points have been loaded!");
746 ROS_ERROR(
"Please choose the correct mission points formation!");
756 _curr.x = msg->pos.x;
757 _curr.y = msg->pos.y;
758 _curr.z = msg->pos.z;
760 mavros_msgs::PositionTarget pos_sp;
762 pos_sp.coordinate_frame = mavros_msgs::PositionTarget::FRAME_LOCAL_NED;
763 pos_sp.position.x = -msg->pos.y;
764 pos_sp.position.y = msg->pos.x;
765 pos_sp.position.z = msg->pos.z;
766 pos_sp.velocity.x = -msg->vel.y;
767 pos_sp.velocity.y = msg->vel.x;
768 pos_sp.velocity.z = msg->vel.z;
769 pos_sp.acceleration_or_force.x = -msg->acc.y;
770 pos_sp.acceleration_or_force.y = msg->acc.x;
771 pos_sp.acceleration_or_force.z = msg->acc.z;
772 double yaw_sp_enu = msg->yaw.x + 1.5708;
774 if (yaw_sp_enu > 3.1415926)
776 yaw_sp_enu -= 3.1415926 * 2;
778 else if (yaw_sp_enu < -3.1415926)
780 yaw_sp_enu += 3.1415926 * 2;
782 pos_sp.yaw = yaw_sp_enu;
784 pos_sp.type_mask = 32768;
801 std::cout <<
"Goto next ref: " <<
_points_id << std::endl;
813 std::cout <<
"Goto next ref: " <<
_points_id << std::endl;
820 ROS_ERROR(
"Please choose the correct mission points formation!");
828 geometry_msgs::Point dist;
834 if (dist.x * dist.x + dist.y * dist.y < 2.0 ||
m_jump)
842 ROS_INFO(
"UAV is landing!");
856 std::cout <<
"Goto wp: " <<
_points_id << std::endl;
866 std_msgs::Byte uav_error;
867 uav_error.data = val;
875 for (
int position = 0; position < 16; position++)
877 bool is_set = (pre_flight_check & (1 << position)) >> position;
884 ROS_ERROR(
"Attitude Roll Error");
887 ROS_ERROR(
"Attitude Pitch Error");
890 ROS_ERROR(
"Attitude Mag North Error");
893 ROS_ERROR(
"Attitude Mag East Error");
896 ROS_ERROR(
"Attitude Mag Z Error");
899 ROS_ERROR(
"Attitude Acc North Error");
902 ROS_ERROR(
"Attitude Acc East Error");
905 ROS_ERROR(
"Attitude Acc Z Error");
908 ROS_ERROR(
"Attitude GPS EPH Error");
911 ROS_ERROR(
"Attitude GPS EPV Error");
914 ROS_ERROR(
"Attitude GPS Velocity North Error");
917 ROS_ERROR(
"Attitude GPS Velocity East Error");
920 ROS_ERROR(
"Attitude GPS Velocity Z Error");
923 ROS_ERROR(
"Attitude GPS Time Error");
926 ROS_ERROR(
"Attitude IMU stuck Error");
929 ROS_INFO(
"All Good!");
951 uint16_t error_state = 0;
952 for (
int position = 0; position < 10; position++)
955 if (position == 0 || position == 4)
959 else if (position == 1)
961 error_state = (in_flight_check & 0x03);
962 switch (
int(error_state))
965 ROS_ERROR(
"Arm Error");
969 ROS_WARN(
"Disarmed");
975 ROS_WARN(
"Pre-Armed");
980 else if (position == 5)
982 error_state = (in_flight_check & 0x30) >> 4;
983 switch (
int(error_state))
989 std::cout << ros::Time::now() <<
" IFC: RTL "
996 std::cout << ros::Time::now() <<
" IFC:Auto-Land "
1002 ROS_ERROR(
"IFC: Flight termination mode triggered.");
1010 bool is_set = (in_flight_check & (1 << position)) >> position;
1016 ROS_ERROR(
"IFC: Soft Geo-fence Violated.");
1020 ROS_ERROR(
"IFC: Hard Geo-fence Violated.");
1024 ROS_ERROR(
"IFC: Battery Low!");
1028 ROS_ERROR(
"IFC: GPS Failed.");
1033 ROS_ERROR(
"IFC:Large Attitude!");
1042 const diagnostic_msgs::DiagnosticArray::ConstPtr &msg)
1045 uint16_t pre_flight_check = 0;
1046 uint16_t in_flight_check = 0;
1048 for (
int i = 0; i < msg->status.size(); i++)
1050 if (msg->status[i].name ==
"mavros: System")
1052 for (
int val = 0; val < msg->status[i].values.size(); val++)
1054 if (msg->status[i].values[val].key ==
"Errors count #3")
1057 std::stoi(msg->status[i].values[val].value);
1060 if (pre_flight_check &&
1067 if (msg->status[i].values[val].key ==
"Errors count #4")
1070 std::stoi(msg->status[i].values[val].value);
1073 if (in_flight_check &&
1077 if (
int(in_flight_check) <= 3)
1087 ROS_ERROR(
"Task Termination is Activated!");
1098 geometry_msgs::PoseStamped
1101 tf::Matrix3x3 R_enu2nwu;
1102 R_enu2nwu.setRPY(0.0, 0.0, -3.1415926 / 2);
1105 tf::Vector3 pos(msg.pose.position.x, msg.pose.position.y,
1106 msg.pose.position.z);
1107 tf::Vector3 pos_nwu = R_enu2nwu * pos;
1109 tf::Quaternion quat(msg.pose.orientation.x, msg.pose.orientation.y,
1110 msg.pose.orientation.z, msg.pose.orientation.w);
1111 tf::Matrix3x3 R(quat);
1112 tf::Matrix3x3 R_nwu = R_enu2nwu * R;
1113 tf::Quaternion quat_nwu;
1114 R_nwu.getRotation(quat_nwu);
1116 geometry_msgs::PoseStamped msg_nwu;
1119 msg_nwu.pose.position.x = pos_nwu[0];
1120 msg_nwu.pose.position.y = pos_nwu[1];
1121 msg_nwu.pose.position.z = pos_nwu[2];
1122 msg_nwu.pose.orientation.x = quat_nwu[0];
1123 msg_nwu.pose.orientation.y = quat_nwu[1];
1124 msg_nwu.pose.orientation.z = quat_nwu[2];
1125 msg_nwu.pose.orientation.w = quat_nwu[3];