使用OSDK/OSDK_ROS 的无人机飞行控制功能,能够设置并获取无人机各项基础参数,控制无人机执行基础飞行动作,通过Joystick 功能控制无人机执行复杂的飞行动作。
Joystick 是一个无人机综合控制功能,使用Joystick 功能时,开发者根据实际的应用需要,通过调用Joystick 中的接口,同时设置无人机使用的坐标系、水平控制的模式、垂直控制的模式、yaw角度控制的模式和悬停模式,才能设计出满足使用需求的无人机飞行控制逻辑。
机体坐标系
机体坐标系以无人机的重心为原点,无人机机头前进的方向为X轴,机头前进方向的右侧为Y轴,Z轴与X轴、Y轴相互垂直交于重心且指向无人机下方(遵循“右手法则”)。在机体坐标下,无人机围绕X轴、Y轴和Z轴旋转时的飞行动作,可称为横滚(无人机仅绕X轴旋转)、俯仰(无人机仅绕Y轴旋转)和偏航(无人机仅绕Z轴旋转)。
大地坐标系
大地坐标系也称世界坐标系或当地水平坐标系,在该坐标系中,无人机指向地球正北的方向为X轴,正东的方向为Y轴,X轴与Y轴相互垂直,Z轴竖直指向无人机下方,在满足“右手法则”的前提下,Z轴将根据无人机飞行的实际情况调节角度,因此该坐标系也称为“北-东-地(N-E-D)坐标系”。
姿态角控制模式:在该模式下,水平方向的指令为无人机的姿态角。(在机体坐标系下,该角度为roll 和pitch)
速度控制模式:在该模式下,水平方向的指令为无人机的速度
位置控制模式:在该模式下,水平方向的指令为无人机的位置
角速度控制:在该模式下,水平方向的指令为无人机的旋转角速度
说明: 当位置指令的模不为0时,无人机会以指定的速度向前飞行,否则,无人机将悬停在指定的位置。
速度控制模式:控制无人机垂直方向的速度
位置控制模式:控制无人机垂直方向的位置,该位置为相对于起飞点的绝对位置
油门控制模式:控制无人机的油门
角度控制模式:在该模式下,yaw方向旋转的指令为yaw 的角度
角速率控制模式:在该模式下,yaw方向旋转的指令为yaw 的角速率
仅在水平控制模式中的速度控制模式下,开发者可以设置无人机的悬停模式:
开启稳定模式:开启稳定模式后,无人机将在指定的位置上悬停
关闭稳定模式:关闭稳定模式后,无人机将按照速度命令飞行,当无人机的前进速度为0时候,无人机可能会随风飘动
使用Joystick 功能需要先设置Joystick 的模式和对应的控制指令,再执行Joystick 指令,实现对无人机的控制。 如下代码以在dji_osdk_ros例子中,使用Joystick 功能控制无人机。
void velocityAndYawRateCtrl(const JoystickCommand &offsetDesired, uint32_t timeMs)
{
double originTime = 0;
double currentTime = 0;
uint64_t elapsedTimeInMs = 0;
SetJoystickMode joystickMode;
JoystickAction joystickAction;
joystickMode.request.horizontal_mode = joystickMode.request.HORIZONTAL_VELOCITY;
joystickMode.request.vertical_mode = joystickMode.request.VERTICAL_VELOCITY;
joystickMode.request.yaw_mode = joystickMode.request.YAW_RATE;
joystickMode.request.horizontal_coordinate = joystickMode.request.HORIZONTAL_GROUND;
joystickMode.request.stable_mode = joystickMode.request.STABLE_ENABLE;
set_joystick_mode_client.call(joystickMode);
joystickAction.request.joystickCommand.x = offsetDesired.x;
joystickAction.request.joystickCommand.y = offsetDesired.y;
joystickAction.request.joystickCommand.z = offsetDesired.z;
joystickAction.request.joystickCommand.yaw = offsetDesired.yaw;
originTime = ros::Time::now().toSec();
currentTime = originTime;
elapsedTimeInMs = (currentTime - originTime)*1000;
while(elapsedTimeInMs <= timeMs)
{
currentTime = ros::Time::now().toSec();
elapsedTimeInMs = (currentTime - originTime) * 1000;
joystick_action_client.call(joystickAction);
}
}
joystickMode.request.horizontal_mode = joystickMode.request.HORIZONTAL_VELOCITY;
joystickMode.request.vertical_mode = joystickMode.request.VERTICAL_VELOCITY;
joystickMode.request.yaw_mode = joystickMode.request.YAW_RATE;
joystickMode.request.horizontal_coordinate = joystickMode.request.HORIZONTAL_GROUND;
joystickMode.request.horizontal_coordinate = joystickMode.request.HORIZONTAL_GROUND;
joystickMode.request.stable_mode = joystickMode.request.STABLE_ENABLE;
通过参考JoystickMode所有参数可以获得所有备选参数。
bool moveByPosOffset(FlightTaskControl& task,const JoystickCommand &offsetDesired,
float posThresholdInM,
float yawThresholdInDeg)
{
task.request.task = FlightTaskControl::Request::TASK_POSITION_AND_YAW_CONTROL;
task.request.joystickCommand.x = offsetDesired.x;
task.request.joystickCommand.y = offsetDesired.y;
task.request.joystickCommand.z = offsetDesired.z;
task.request.joystickCommand.yaw = offsetDesired.yaw;
task.request.posThresholdInM = posThresholdInM;
task.request.yawThresholdInDeg = yawThresholdInDeg;
task_control_client.call(task);
return task.response.result;
}
task.request.task = FlightTaskControl::Request::TASK_POSITION_AND_YAW_CONTROL;
这是一种快捷的设置方式,具体请参考JoystickMode相关
如何利用joystickMode功能,扩展出更强大和灵活的无人机飞行控制功能 ? 例如:如何实现控制无人机运动速度(包括运动方向)的同时也能控制其运动位移和方位角 ?
期待你的见解…
dji_osdk_ros例子
JoystickMode所有参数
JoystickMode常用模式