Task manager is used as a central module to communicate with other modules. More...
#include <ddrone_task_manager.h>
Public Member Functions | |
void | approachCallback (const std_msgs::Bool::ConstPtr &msg) |
approach command for kerrigan project More... | |
void | calculateYaw () |
Calculate yaw angle from current attitude. More... | |
void | checkReached () |
check if the uav reached the waypoint More... | |
void | clearMission () |
Clear misson. More... | |
void | currentStateCallback (const common_msgs::state::ConstPtr &msg) |
obtain current uav state More... | |
void | diagnosticsCallback (const diagnostic_msgs::DiagnosticArray::ConstPtr &msg) |
Analyse preflight and inflight check for UAV. More... | |
void | engine0 () |
removed for px4 1.8 version More... | |
void | gpsCurCb (const sensor_msgs::NavSatFix::ConstPtr &msg) |
Get UAV current GPS location. More... | |
void | gpsHomeCb (const mavros_msgs::HomePosition::ConstPtr &msg) |
Get GPS home location. More... | |
void | inFlightCheck (uint16_t &in_flight_check) |
inflight Check More... | |
void | jumpWp () |
jump one waypoint in list More... | |
void | jumpWpCallback (const std_msgs::Bool::ConstPtr &msg) |
Skip current waypoint. More... | |
bool | landCb () |
call landing service More... | |
bool | loadMission () |
load mission from UI or files More... | |
void | missionCallback (int8_t msg) |
mission handler More... | |
void | missionTimer (const ros::TimerEvent &) |
callback function for running mission (default: 0.2) More... | |
void | onlineCallback (const std_msgs::Bool::ConstPtr &msg) |
Landing triggered by offline status (msg: false) More... | |
void | posTgtCallback (const geometry_msgs::Point::ConstPtr &msg) |
get gps position command and transfer it into UAV local coordinate More... | |
void | posYawTgtCallback (const common_msgs::target::ConstPtr &msg) |
get position and yaw command More... | |
void | preFlightCheck (uint16_t &pre_flight_check) |
preflight Check More... | |
void | pubErrorState (std::int8_t val) |
Publish Error State from preflight and inflight state. More... | |
void | pubGpstgt () |
Convert target from GPS into ENU coordinate. More... | |
void | pubTarget (bool controlMode, float tgtX, float tgtY, float tgtZ) |
publish local target with control mode: More... | |
void | pubTargetWYaw (bool controlMode, float tgtX, float tgtY, float tgtZ, float yaw) |
publish local target with yaw, and set control mode: More... | |
void | shutdownSwarm () |
shutdown Swarm More... | |
void | takeoff () |
Take off. More... | |
TaskManager (ros::NodeHandle &nodeHandle) | |
void | uavPoseCallback (const geometry_msgs::PoseStamped::ConstPtr &msg) |
get current uav pose More... | |
void | uavStateCb (const mavros_msgs::State::ConstPtr &msg) |
Get UAV hardware state: connected/armed/guided/mode. More... | |
void | uiPointsCallback (const geometry_msgs::Polygon::ConstPtr &msg) |
points for UI (lagacy function) More... | |
void | velTgtCallback (const geometry_msgs::Point::ConstPtr &msg) |
get velocity command More... | |
void | velYawTgtCallback (const common_msgs::target::ConstPtr &msg) |
get velocity and yaw command More... | |
void | webCmdCallback (const std_msgs::Byte::ConstPtr &msg) |
Get command from web GCS and pass to mission callback. More... | |
~TaskManager () | |
Private Member Functions | |
geometry_msgs::PoseStamped | transform_orientation_enu_nwu (geometry_msgs::PoseStamped) |
transform orientation from enu to nwu More... | |
Private Attributes | |
geometry_msgs::Point | _curr |
current uav position More... | |
double | _flightHeight |
takeoff flight height More... | |
double | _missionPeriod |
mission call back period: 0.2s More... | |
ros::NodeHandle | _nh |
ros node handle More... | |
int | _points_id |
Using this value to label points read from a file. More... | |
int | _points_source_param |
Points from 0: local waypoints file; 1: refrence waypoints file; 2: ui selected waypoints; 3:velocity points from file. More... | |
std::vector< common_msgs::state > | _ref_list |
reference list from file More... | |
double | _relativeHeight |
height relative to the ground More... | |
bool | _simulation |
simulation mode is on if true More... | |
std::vector< geometry_msgs::Point > | _wp_list |
waypoint list from file More... | |
ros::ServiceClient | arming_client |
/mavros/cmd/arming service More... | |
ros::ServiceClient | client_engine0 |
removed service More... | |
ros::ServiceClient | client_home |
/mavros/cmd/set_home service More... | |
double | cos_y |
std_msgs::Bool | engage_msg |
removed More... | |
GpsUtils | gpsToEnu |
current gps target(from user) to enu local frame More... | |
GpsUtils | gpsToEnuCur |
current gps(from px4) to enu local frame More... | |
bool | inPcmdMode |
position command flag More... | |
ros::ServiceClient | land_client |
/mavros/cmd/land service More... | |
uint16_t | last_in_flight_check |
previous inflight check More... | |
uint16_t | last_pre_flight_check |
precious preflight check More... | |
bool | m_approach |
approach flag More... | |
ros::Subscriber | m_approach_cmd_sub |
subscribe /swarm/approach More... | |
ros::Subscriber | m_current_state_sub |
subscribe refrence: /rt_ref_gen/current_state More... | |
ros::Subscriber | m_diagnostics_sub |
subscribe /diagnostics More... | |
ros::Publisher | m_engage_pub |
ros::Publisher | m_error_state_pub |
error stater publisher (for UI): /task_manager/error_state More... | |
ros::Subscriber | m_gcs_cmd_sub |
sensor_msgs::NavSatFix | m_gps_cur |
current gps location More... | |
ros::Subscriber | m_gps_cur_sub |
subscribe /mavros/global_position/global More... | |
mavros_msgs::HomePosition | m_gps_home |
GPS home location. More... | |
ros::Subscriber | m_gps_home_sub |
subscribe /mavros/home_position/home More... | |
bool | m_jump |
ros::Subscriber | m_mission_sub |
subscribe mission from UI: /mission_from_ui More... | |
ros::Timer | m_mission_timer |
mission call back timer More... | |
ros::Publisher | m_mpc_pos_init_pub |
mpc initial position publisher: /task_manager/mpc_init_position_nwu More... | |
ros::Subscriber | m_online_status_sub |
subscribe /swarm/online More... | |
ros::Subscriber | m_pcmd_sub |
subscribe /posTgtFromSwarm More... | |
std::string | m_points_location |
set waypoint location: /home/nvidia(default) More... | |
ros::Publisher | m_pos_cmd_pub |
way points publisher: /dummy/pos_cmd More... | |
ros::Publisher | m_ref_pub |
refrence from file publisher: /task_manager/current_state More... | |
ros::Subscriber | m_skipCurPoint_sub |
subscribe /mission_skip_point More... | |
std_msgs::Bool | m_swarm |
swarm flag More... | |
ros::Publisher | m_swarm_pub |
trigger swarm publisher: /task_manager/swarm More... | |
common_msgs::target | m_tgt |
current target point More... | |
ros::Publisher | m_tgt_pub |
target publisher: /nndp_cpp/tgt More... | |
geometry_msgs::PoseStamped | m_uav_pose |
current pose(enu) from /mavros/local_position/pose More... | |
geometry_msgs::PoseStamped | m_uav_pose_enu |
geometry_msgs::PoseStamped | m_uav_pose_nwu |
current pose in nwu More... | |
ros::Subscriber | m_uav_pose_sub |
subscribe current uav pose: /mavros/local_position/pose to update m_uav_pose More... | |
geometry_msgs::Polygon | m_ui_points |
polygon points from UI More... | |
ros::Subscriber | m_ui_points_sub |
subscribe points from UI: /points_from_ui More... | |
ros::Subscriber | m_vcmd_sub |
subscribe /velTgtFromSwarm More... | |
ros::Publisher | MPC_Position_Initial_Pub |
UavTaskState | mUavTaskState |
UAV current state: checkout enum UavTaskState. More... | |
geometry_msgs::Point | pos_init |
the inital position of mission; More... | |
ros::Publisher | Position_Setpoint_Pub |
Setpoints to MAVROS publisher: /mavros/setpoint_raw/local. More... | |
ros::ServiceClient | set_mode_client |
/mavros/set_mode service More... | |
double | sin_y |
ros::Publisher | swarm_pos_pub |
publish position in nwu: /task_manager/position_nwu More... | |
bool | TaskTerminateFlag |
task terminate flag when inflight or preflight check failed More... | |
mavros_msgs::State | uav_current_state |
uav hardware sate from /mavros/state More... | |
ros::Subscriber | uav_state_sub |
subscribe /mavros/state More... | |
bool | ui_points_selected |
flag showing points selected from UI More... | |
double | yaw_ |
param for calculating yaw More... | |
bool | yaw_control_ |
flag set to control yaw More... | |
double | yaw_init |
initial yaw in enu frame More... | |
double | yaw_init_enu |
initial yaw in enu frame More... | |
double | yaw_init_nwu |
initial yaw in nwu frame More... | |
bool | yaw_initialized |
flag showing yaw is initialized More... | |
Task manager is used as a central module to communicate with other modules.
For example it gets UAV states from the fligt controller, obtains commands from users and sends processed command to planning module. It will also detect abonormals and give feedback to users.
Definition at line 130 of file ddrone_task_manager.h.
TaskManager::TaskManager | ( | ros::NodeHandle & | nodeHandle | ) |
Definition at line 9 of file ddrone_task_manager.cpp.
TaskManager::~TaskManager | ( | ) |
Definition at line 110 of file ddrone_task_manager.cpp.
void TaskManager::approachCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
approach command for kerrigan project
UAV will fly 15 meter to south direction
Definition at line 211 of file ddrone_task_manager.cpp.
void TaskManager::calculateYaw | ( | ) |
Calculate yaw angle from current attitude.
Definition at line 566 of file ddrone_task_manager.cpp.
void TaskManager::checkReached | ( | ) |
check if the uav reached the waypoint
Definition at line 825 of file ddrone_task_manager.cpp.
void TaskManager::clearMission | ( | ) |
Clear misson.
clear value in waypoints and reference list set target to current location
Definition at line 606 of file ddrone_task_manager.cpp.
void TaskManager::currentStateCallback | ( | const common_msgs::state::ConstPtr & | msg | ) |
obtain current uav state
Definition at line 753 of file ddrone_task_manager.cpp.
void TaskManager::diagnosticsCallback | ( | const diagnostic_msgs::DiagnosticArray::ConstPtr & | msg | ) |
Analyse preflight and inflight check for UAV.
Definition at line 1041 of file ddrone_task_manager.cpp.
void TaskManager::engine0 | ( | ) |
removed for px4 1.8 version
Definition at line 506 of file ddrone_task_manager.cpp.
void TaskManager::gpsCurCb | ( | const sensor_msgs::NavSatFix::ConstPtr & | msg | ) |
Get UAV current GPS location.
Definition at line 242 of file ddrone_task_manager.cpp.
void TaskManager::gpsHomeCb | ( | const mavros_msgs::HomePosition::ConstPtr & | msg | ) |
Get GPS home location.
Definition at line 237 of file ddrone_task_manager.cpp.
void TaskManager::inFlightCheck | ( | uint16_t & | in_flight_check | ) |
inflight Check
Definition at line 938 of file ddrone_task_manager.cpp.
void TaskManager::jumpWp | ( | ) |
jump one waypoint in list
void TaskManager::jumpWpCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Skip current waypoint.
Definition at line 560 of file ddrone_task_manager.cpp.
bool TaskManager::landCb | ( | ) |
call landing service
Definition at line 470 of file ddrone_task_manager.cpp.
bool TaskManager::loadMission | ( | ) |
load mission from UI or files
[in] | swarm_pos_pub |
Definition at line 616 of file ddrone_task_manager.cpp.
void TaskManager::missionCallback | ( | int8_t | msg | ) |
mission handler
value | for switching cases 1: takeoff, 2: mission, 3: swarm, 4: hover, 5: land |
Definition at line 266 of file ddrone_task_manager.cpp.
void TaskManager::missionTimer | ( | const ros::TimerEvent & | ) |
callback function for running mission (default: 0.2)
Definition at line 788 of file ddrone_task_manager.cpp.
void TaskManager::onlineCallback | ( | const std_msgs::Bool::ConstPtr & | msg | ) |
Landing triggered by offline status (msg: false)
Definition at line 228 of file ddrone_task_manager.cpp.
void TaskManager::posTgtCallback | ( | const geometry_msgs::Point::ConstPtr & | msg | ) |
get gps position command and transfer it into UAV local coordinate
Definition at line 183 of file ddrone_task_manager.cpp.
void TaskManager::posYawTgtCallback | ( | const common_msgs::target::ConstPtr & | msg | ) |
get position and yaw command
Definition at line 155 of file ddrone_task_manager.cpp.
void TaskManager::preFlightCheck | ( | uint16_t & | pre_flight_check | ) |
preflight Check
Definition at line 873 of file ddrone_task_manager.cpp.
void TaskManager::pubErrorState | ( | std::int8_t | val | ) |
Publish Error State from preflight and inflight state.
Definition at line 864 of file ddrone_task_manager.cpp.
void TaskManager::pubGpstgt | ( | ) |
Convert target from GPS into ENU coordinate.
Definition at line 592 of file ddrone_task_manager.cpp.
void TaskManager::pubTarget | ( | bool | controlMode, |
float | tgtX, | ||
float | tgtY, | ||
float | tgtZ | ||
) |
publish local target with control mode:
controlMode,0:POS_CONTROL,1:VEL_CONTROL |
Definition at line 126 of file ddrone_task_manager.cpp.
void TaskManager::pubTargetWYaw | ( | bool | controlMode, |
float | tgtX, | ||
float | tgtY, | ||
float | tgtZ, | ||
float | yaw | ||
) |
publish local target with yaw, and set control mode:
controlMode,0:POS_CONTROL,1:VEL_CONTROL |
Definition at line 137 of file ddrone_task_manager.cpp.
void TaskManager::shutdownSwarm | ( | ) |
shutdown Swarm
stop subscring pcmd and vcmd set swarm to false to shutdown swarm algo
Definition at line 201 of file ddrone_task_manager.cpp.
void TaskManager::takeoff | ( | ) |
Take off.
Make Sure FCU is connected, wait for 5s if not connected. send a few setpoints before starting set the inital position of mission start set MPC Initial Set UAV mode to offboard and arm the vehicle
Definition at line 367 of file ddrone_task_manager.cpp.
|
private |
transform orientation from enu to nwu
Definition at line 1099 of file ddrone_task_manager.cpp.
void TaskManager::uavPoseCallback | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) |
get current uav pose
Definition at line 115 of file ddrone_task_manager.cpp.
void TaskManager::uavStateCb | ( | const mavros_msgs::State::ConstPtr & | msg | ) |
Get UAV hardware state: connected/armed/guided/mode.
Definition at line 246 of file ddrone_task_manager.cpp.
void TaskManager::uiPointsCallback | ( | const geometry_msgs::Polygon::ConstPtr & | msg | ) |
points for UI (lagacy function)
Definition at line 553 of file ddrone_task_manager.cpp.
void TaskManager::velTgtCallback | ( | const geometry_msgs::Point::ConstPtr & | msg | ) |
get velocity command
Definition at line 176 of file ddrone_task_manager.cpp.
void TaskManager::velYawTgtCallback | ( | const common_msgs::target::ConstPtr & | msg | ) |
get velocity and yaw command
Definition at line 149 of file ddrone_task_manager.cpp.
void TaskManager::webCmdCallback | ( | const std_msgs::Byte::ConstPtr & | msg | ) |
Get command from web GCS and pass to mission callback.
Definition at line 260 of file ddrone_task_manager.cpp.
|
private |
current uav position
Definition at line 336 of file ddrone_task_manager.h.
|
private |
takeoff flight height
Definition at line 344 of file ddrone_task_manager.h.
|
private |
mission call back period: 0.2s
Definition at line 352 of file ddrone_task_manager.h.
|
private |
ros node handle
Definition at line 307 of file ddrone_task_manager.h.
|
private |
Using this value to label points read from a file.
Definition at line 353 of file ddrone_task_manager.h.
|
private |
Points from 0: local waypoints file; 1: refrence waypoints file; 2: ui selected waypoints; 3:velocity points from file.
Definition at line 354 of file ddrone_task_manager.h.
|
private |
reference list from file
Definition at line 335 of file ddrone_task_manager.h.
|
private |
height relative to the ground
Definition at line 345 of file ddrone_task_manager.h.
|
private |
simulation mode is on if true
Definition at line 372 of file ddrone_task_manager.h.
|
private |
waypoint list from file
Definition at line 334 of file ddrone_task_manager.h.
|
private |
/mavros/cmd/arming service
Definition at line 359 of file ddrone_task_manager.h.
|
private |
removed service
Definition at line 356 of file ddrone_task_manager.h.
|
private |
/mavros/cmd/set_home service
Definition at line 357 of file ddrone_task_manager.h.
|
private |
Definition at line 365 of file ddrone_task_manager.h.
|
private |
removed
Definition at line 361 of file ddrone_task_manager.h.
|
private |
current gps target(from user) to enu local frame
Definition at line 375 of file ddrone_task_manager.h.
|
private |
current gps(from px4) to enu local frame
Definition at line 376 of file ddrone_task_manager.h.
|
private |
position command flag
Definition at line 378 of file ddrone_task_manager.h.
|
private |
/mavros/cmd/land service
Definition at line 358 of file ddrone_task_manager.h.
|
private |
previous inflight check
Definition at line 379 of file ddrone_task_manager.h.
|
private |
precious preflight check
Definition at line 380 of file ddrone_task_manager.h.
|
private |
approach flag
Definition at line 374 of file ddrone_task_manager.h.
|
private |
subscribe /swarm/approach
Definition at line 328 of file ddrone_task_manager.h.
|
private |
subscribe refrence: /rt_ref_gen/current_state
Definition at line 319 of file ddrone_task_manager.h.
|
private |
subscribe /diagnostics
Definition at line 329 of file ddrone_task_manager.h.
|
private |
Definition at line 311 of file ddrone_task_manager.h.
|
private |
error stater publisher (for UI): /task_manager/error_state
Definition at line 313 of file ddrone_task_manager.h.
|
private |
Definition at line 330 of file ddrone_task_manager.h.
|
private |
current gps location
Definition at line 364 of file ddrone_task_manager.h.
|
private |
subscribe /mavros/global_position/global
Definition at line 327 of file ddrone_task_manager.h.
|
private |
GPS home location.
Definition at line 363 of file ddrone_task_manager.h.
|
private |
subscribe /mavros/home_position/home
Definition at line 326 of file ddrone_task_manager.h.
|
private |
Definition at line 350 of file ddrone_task_manager.h.
|
private |
subscribe mission from UI: /mission_from_ui
Definition at line 320 of file ddrone_task_manager.h.
|
private |
mission call back timer
Definition at line 351 of file ddrone_task_manager.h.
|
private |
mpc initial position publisher: /task_manager/mpc_init_position_nwu
Definition at line 314 of file ddrone_task_manager.h.
|
private |
subscribe /swarm/online
Definition at line 331 of file ddrone_task_manager.h.
|
private |
subscribe /posTgtFromSwarm
Definition at line 325 of file ddrone_task_manager.h.
|
private |
set waypoint location: /home/nvidia(default)
Definition at line 355 of file ddrone_task_manager.h.
|
private |
way points publisher: /dummy/pos_cmd
Definition at line 308 of file ddrone_task_manager.h.
|
private |
refrence from file publisher: /task_manager/current_state
Definition at line 309 of file ddrone_task_manager.h.
|
private |
subscribe /mission_skip_point
Definition at line 323 of file ddrone_task_manager.h.
|
private |
swarm flag
Definition at line 373 of file ddrone_task_manager.h.
|
private |
trigger swarm publisher: /task_manager/swarm
Definition at line 312 of file ddrone_task_manager.h.
|
private |
current target point
Definition at line 343 of file ddrone_task_manager.h.
|
private |
target publisher: /nndp_cpp/tgt
Definition at line 310 of file ddrone_task_manager.h.
|
private |
current pose(enu) from /mavros/local_position/pose
Definition at line 338 of file ddrone_task_manager.h.
|
private |
Definition at line 340 of file ddrone_task_manager.h.
|
private |
current pose in nwu
Definition at line 341 of file ddrone_task_manager.h.
|
private |
subscribe current uav pose: /mavros/local_position/pose to update m_uav_pose
Definition at line 322 of file ddrone_task_manager.h.
|
private |
polygon points from UI
Definition at line 362 of file ddrone_task_manager.h.
|
private |
subscribe points from UI: /points_from_ui
Definition at line 321 of file ddrone_task_manager.h.
|
private |
subscribe /velTgtFromSwarm
Definition at line 324 of file ddrone_task_manager.h.
|
private |
Definition at line 316 of file ddrone_task_manager.h.
|
private |
UAV current state: checkout enum UavTaskState.
Definition at line 347 of file ddrone_task_manager.h.
|
private |
the inital position of mission;
Definition at line 369 of file ddrone_task_manager.h.
|
private |
Setpoints to MAVROS publisher: /mavros/setpoint_raw/local.
Definition at line 315 of file ddrone_task_manager.h.
|
private |
/mavros/set_mode service
Definition at line 360 of file ddrone_task_manager.h.
|
private |
Definition at line 365 of file ddrone_task_manager.h.
|
private |
publish position in nwu: /task_manager/position_nwu
Definition at line 317 of file ddrone_task_manager.h.
|
private |
task terminate flag when inflight or preflight check failed
Definition at line 377 of file ddrone_task_manager.h.
|
private |
uav hardware sate from /mavros/state
Definition at line 382 of file ddrone_task_manager.h.
|
private |
subscribe /mavros/state
Definition at line 332 of file ddrone_task_manager.h.
|
private |
flag showing points selected from UI
Definition at line 371 of file ddrone_task_manager.h.
|
private |
param for calculating yaw
Definition at line 365 of file ddrone_task_manager.h.
|
private |
flag set to control yaw
Definition at line 381 of file ddrone_task_manager.h.
|
private |
initial yaw in enu frame
Definition at line 368 of file ddrone_task_manager.h.
|
private |
initial yaw in enu frame
Definition at line 367 of file ddrone_task_manager.h.
|
private |
initial yaw in nwu frame
Definition at line 366 of file ddrone_task_manager.h.
|
private |
flag showing yaw is initialized
Definition at line 370 of file ddrone_task_manager.h.