Class FlightControlModule
Defined in File flight_control.hpp
Inheritance Relationships
Base Type
public rclcpp_lifecycle::LifecycleNode
Class Documentation
-
class psdk_ros2::FlightControlModule : public rclcpp_lifecycle::LifecycleNode
Public Functions
-
explicit FlightControlModule(const std::string &name)
Construct a new FlightControlModule object.
- Parameters
node_name – Name of the node
-
~FlightControlModule()
Destroy the Flight Control Module object.
-
CallbackReturn on_configure(const rclcpp_lifecycle::State &state)
Configures the flight control module. Creates the ROS 2 subscribers and services.
- Parameters
state – rclcpp_lifecycle::State. Current state of the node.
- Returns
CallbackReturn SUCCESS or FAILURE
-
CallbackReturn on_activate(const rclcpp_lifecycle::State &state)
Activates the flight control module.
- Parameters
state – rclcpp_lifecycle::State. Current state of the node.
- Returns
CallbackReturn SUCCESS or FAILURE
-
CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state)
Cleans the flight control module. Resets the ROS 2 subscribers and services.
- Parameters
state – rclcpp_lifecycle::State. Current state of the node.
- Returns
CallbackReturn SUCCESS or FAILURE
-
CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state)
Deactivates the flight control module.
- Parameters
state – rclcpp_lifecycle::State. Current state of the node.
- Returns
CallbackReturn SUCCESS or FAILURE
-
CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state)
Shuts down the flight control module.
- Parameters
state – rclcpp_lifecycle::State. Current state of the node.
- Returns
CallbackReturn SUCCESS or FAILURE
Initialize the flight control module. It needs the RID information to be passed to the native flight control initialization function from DJI.
- Parameters
current_gps_position – sensor_msgs::msg::NavSatFix. Current GPS
- Returns
true/false
-
bool deinit()
Deinitialize the flight control module.
- Returns
true/false
Private Functions
Callback function to control aircraft position and yaw. This function expects the commands to be given with respect to a global ENU frame.
- Parameters
msg – sensor_msgs::msg::Joy. Axes represent the x [m], y [m], z [m] and yaw [rad] command.
Callback function to control aircraft velocity and yaw rate. This function expects the commands to be given with respect to a global ENU frame.
- Parameters
msg – sensor_msgs::msg::Joy. Axes represent the x [m/s], y [m/s], z [m/s] and yaw [rad/s] command.
Callback function to control aircraft velocity and yaw. This function expects the commands to be given with respect to a FLU body frame.
- Parameters
msg – sensor_msgs::msg::Joy. Axes represent the x [m/s], y [m/s], z [m/s] and yaw [rad/s] command.
Callback function to control roll, pitch, yaw rate and thrust. This function expects the commands to be given with respect to a FLU body frame.
Note
This type of control is not implemented at this moment.
- Parameters
msg – sensor_msgs::msg::Joy. Axes represent the x [rad], y [rad], thrust value percentage [0-100%] and yaw rate [rad/s] command.
Callback function to exposing a generic control method of the aircraft.The type of commands as well as the reference frame is specified in a flag within the msg.
- Parameters
msg – sensor_msgs::msg::Joy. Axes represent the x, y, z, yaw and flag command.
Sets the home position from GPS data. The user inputs the latitude and longitude which will represent the new home position.
- Parameters
request – SetHomeFromGPS service request
response – SetHomeFromGPS service response
Sets the home position at the current GPS location.
- Parameters
request – Trigger service request
response – Trigger service response
Sets the go home altitude to the requested user defined altitude.
Note
If aircraft’s current altitude is higher than the setting value of go home altitude, aircraft will go home using current altitude. Otherwise, it will climb to setting of go home altitude, and then execute go home action. Go home altitude setting is 20m ~ 500m.
- Parameters
request – SetGoHomeAltitude service request
response – SetGoHomeAltitude service response
Get the current go home altitude in [m].
- Parameters
request – GetGoHomeAltitude service request
response – GetGoHomeAltitude service response
Request go home action.
- Parameters
request – Trigger service request
response – Trigger service response
Cancel go home action.
- Parameters
request – Trigger service request
response – Trigger service response
Request control authority.
Note
The RC must be in P-mode for this request to be successful.
- Parameters
request – Trigger service request
response – Trigger service response
Release control authority.
Note
The RC must be in P-mode for this request to be successful.
- Parameters
request – Trigger service request
response – Trigger service response
Turn ON motors while copter is on the ground.
- Parameters
request – Trigger service request
response – Trigger service response
Turn OFF motors while copter is on the ground.
- Parameters
request – Trigger service request
response – Trigger service response
Request Take-off action while copter is on the ground.
- Parameters
request – Trigger service request
response – Trigger service response
Request Landing action while copter is in the air.
- Parameters
request – Trigger service request
response – Trigger service response
Cancel Landing action while copter is landing.
- Parameters
request – Trigger service request
response – Trigger service response
Confirm coptere landing when this is 0.7 m above the ground.
Note
When the clearance between the aircraft and the ground is less than 0.7m, the aircraft will pause landing and wait for user’s confirmation. If the ground is not suitable for landing ,user must use RC to control it landing manually or force landing.
- Parameters
request – Trigger service request
response – Trigger service response
Force copter landing.
Note
The smart landing functions will be ignored and the copter will land directly without waiting for user confirmation at 0.7m above ground. Use this function carefully!
- Parameters
request – Trigger service request
response – Trigger service response
Enable/Disable horizontal (forwards,backwards,left and right) visual obstacle avoidance sensors.
- Parameters
request – SetObstacleAvoidance service request
response – SetObstacleAvoidance service response
Enable/Disable horizontal radar obstacle avoidance.
Note
It will only be valid only if CSM radar is installed.
- Parameters
request – SetObstacleAvoidance service request
response – SetObstacleAvoidance service response
Enable/Disable upwards visual obstacle avoidance.
- Parameters
request – SetObstacleAvoidance service request
response – SetObstacleAvoidance service response
Enable/Disable upwards radar obstacle avoidance.
Note
It will only be valid only if CSM radar is installed.
- Parameters
request – SetObstacleAvoidance service request
response – SetObstacleAvoidance service response
Enable/Disable downwards visual obstacle avoidance.
- Parameters
request – SetObstacleAvoidance service request
response – SetObstacleAvoidance service response
Get status of horizontal visual obstacle avoidance.
- Parameters
request – GetObstacleAvoidance service request
response – GetObstacleAvoidance service response
Get status of horizontal radar obstacle avoidance.
- Parameters
request – GetObstacleAvoidance service request
response – GetObstacleAvoidance service response
Get status of downwards visual obstacle avoidance.
- Parameters
request – GetObstacleAvoidance service request
response – GetObstacleAvoidance service response
Get status of upwards visual obstacle avoidance.
- Parameters
request – GetObstacleAvoidance service request
response – GetObstacleAvoidance service response
Get status of upwards radar obstacle avoidance.
- Parameters
request – GetObstacleAvoidance service request
response – GetObstacleAvoidance service response
-
void set_horizontal_mode(float x_cmd, float y_cmd, float z_cmd, float yaw_cmd, uint8_t flag)
Sets horizontal control mode as per flag, updates x, y, and z values and sets Joystick mode.
-
void set_vertical_mode(float x_cmd, float y_cmd, float z_cmd, float yaw_cmd, uint8_t flag)
Sets vertical control mode as per, flag updates x, y, and z values and sets Joystick mode.
-
void set_yaw_mode(float x_cmd, float y_cmd, float z_cmd, float yaw_cmd, uint8_t flag)
Sets yaw control mode as per flag, updates yaw value and sets Joystick mode.
-
explicit FlightControlModule(const std::string &name)