无人机仿真XTDrone学习六:XTDrone键盘控制无人机multirotor_communication.py程序分析三

2023-05-16

multirotor_communication.py程序

这个程序是实现对无人机控制的主要程序,需要重点分析。可以实现对无人机的位置,速度,加速度的控制。
主要节点:

sys.argv[1]+'_'+sys.argv[2]+"_communication"
#根据传入参数进行设置。

话题订阅:

/"self.vehicle_type+'_'+self.vehicle_id+"/mavros/local_position/pose(geometry_msgs/PoseStamped)
# 订阅mavros发布的位姿
/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd(std_msgs/String)
# 订阅外部程序发布的状态控制命令
/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_pose_flu(geometry_msgs/Pose)
/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_pose_enu(geometry_msgs/Pose)
# 订阅外部程序发布的位置控制命令
/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_vel_flu(geometry_msgs/Twist)
/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_vel_enu(geometry_msgs/Twist)
# 订阅外部程序发布的速度控制命令
/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_accel_flu(geometry_msgs/Twist)
/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_accel_enu(geometry_msgs/Twist)
# 订阅外部程序发布的加速度控制命令

话题发布:

self.vehicle_type+'_'+self.vehicle_id+"/mavros/setpoint_raw/local(mavros_msgs/PositionTarget)
# 向mavros发布计算后的目标指令

服务:

self.vehicle_type+'_'+self.vehicle_id+"/mavros/cmd/arming(mavros_msgs/CommandBool)
# 从mavros获取无人机是否上锁
self.vehicle_type+'_'+self.vehicle_id+"/mavros/set_mode(mavros_msgs/SetMode)
# 从mavros获取无人机飞行模式

全部代码:

import rospy
from mavros_msgs.msg import PositionTarget
from mavros_msgs.srv import CommandBool, SetMode
from geometry_msgs.msg import PoseStamped, Pose, Twist
from std_msgs.msg import String
from pyquaternion import Quaternion
import sys

rospy.init_node(sys.argv[1]+'_'+sys.argv[2]+"_communication")
rate = rospy.Rate(30)

class Communication:

    def __init__(self, vehicle_type, vehicle_id):
        
        self.vehicle_type = vehicle_type
        self.vehicle_id = vehicle_id
        self.current_position = None
        self.current_yaw = 0
        self.hover_flag = 0
        self.target_motion = PositionTarget()
        self.arm_state = False
        self.motion_type = 0
        self.flight_mode = None
        self.mission = None
        self.last_cmd = None
            
        '''
        ros subscribers
        '''
        self.local_pose_sub = rospy.Subscriber(self.vehicle_type+'_'+self.vehicle_id+"/mavros/local_position/pose", PoseStamped, self.local_pose_callback,queue_size=1)
        self.cmd_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd",String,self.cmd_callback,queue_size=3)
        self.cmd_pose_flu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_pose_flu", Pose, self.cmd_pose_flu_callback,queue_size=1)
        self.cmd_pose_enu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_pose_enu", Pose, self.cmd_pose_enu_callback,queue_size=1)
        self.cmd_vel_flu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_vel_flu", Twist, self.cmd_vel_flu_callback,queue_size=1)
        self.cmd_vel_enu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_vel_enu", Twist, self.cmd_vel_enu_callback,queue_size=1)
        self.cmd_accel_flu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_accel_flu", Twist, self.cmd_accel_flu_callback,queue_size=1)
        self.cmd_accel_enu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_accel_enu", Twist, self.cmd_accel_enu_callback,queue_size=1)
            
        ''' 
        ros publishers
        '''
        self.target_motion_pub = rospy.Publisher(self.vehicle_type+'_'+self.vehicle_id+"/mavros/setpoint_raw/local", PositionTarget, queue_size=1)

        '''
        ros services
        '''
        self.armService = rospy.ServiceProxy(self.vehicle_type+'_'+self.vehicle_id+"/mavros/cmd/arming", CommandBool)
        self.flightModeService = rospy.ServiceProxy(self.vehicle_type+'_'+self.vehicle_id+"/mavros/set_mode", SetMode)

        print(self.vehicle_type+'_'+self.vehicle_id+": "+"communication initialized")

    def start(self):
        '''
        main ROS thread
        '''
        while not rospy.is_shutdown():
            self.target_motion_pub.publish(self.target_motion)
            rate.sleep()

    def local_pose_callback(self, msg):
        self.current_position = msg.pose.position
        self.current_yaw = self.q2yaw(msg.pose.orientation)

    def construct_target(self, x=0, y=0, z=0, vx=0, vy=0, vz=0, afx=0, afy=0, afz=0, yaw=0, yaw_rate=0):
        target_raw_pose = PositionTarget()
        target_raw_pose.coordinate_frame = self.coordinate_frame
        
        target_raw_pose.position.x = x
        target_raw_pose.position.y = y
        target_raw_pose.position.z = z

        target_raw_pose.velocity.x = vx
        target_raw_pose.velocity.y = vy
        target_raw_pose.velocity.z = vz
        
        target_raw_pose.acceleration_or_force.x = afx
        target_raw_pose.acceleration_or_force.y = afy
        target_raw_pose.acceleration_or_force.z = afz

        target_raw_pose.yaw = yaw
        target_raw_pose.yaw_rate = yaw_rate

        if(self.motion_type == 0):
            target_raw_pose.type_mask = PositionTarget.IGNORE_VX + PositionTarget.IGNORE_VY + PositionTarget.IGNORE_VZ \
                            + PositionTarget.IGNORE_AFX + PositionTarget.IGNORE_AFY + PositionTarget.IGNORE_AFZ \
                            + PositionTarget.IGNORE_YAW_RATE
        if(self.motion_type == 1):
            target_raw_pose.type_mask = PositionTarget.IGNORE_PX + PositionTarget.IGNORE_PY + PositionTarget.IGNORE_PZ \
                            + PositionTarget.IGNORE_AFX + PositionTarget.IGNORE_AFY + PositionTarget.IGNORE_AFZ \
                            + PositionTarget.IGNORE_YAW
        if(self.motion_type == 2):
            target_raw_pose.type_mask = PositionTarget.IGNORE_PX + PositionTarget.IGNORE_PY + PositionTarget.IGNORE_PZ \
                            + PositionTarget.IGNORE_VX + PositionTarget.IGNORE_VY + PositionTarget.IGNORE_VZ \
                            + PositionTarget.IGNORE_YAW

        return target_raw_pose

    def cmd_pose_flu_callback(self, msg):
        self.coordinate_frame = 9
        self.motion_type = 0
        yaw = self.q2yaw(msg.orientation)
        self.target_motion = self.construct_target(x=msg.position.x,y=msg.position.y,z=msg.position.z,yaw=yaw)
 
    def cmd_pose_enu_callback(self, msg):
        self.coordinate_frame = 1
        self.motion_type = 0
        yaw = self.q2yaw(msg.orientation)
        self.target_motion = self.construct_target(x=msg.position.x,y=msg.position.y,z=msg.position.z,yaw=yaw)
        
    def cmd_vel_flu_callback(self, msg):
        self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
        if self.hover_flag == 0:
            self.coordinate_frame = 8
            self.motion_type = 1
            self.target_motion = self.construct_target(vx=msg.linear.x,vy=msg.linear.y,vz=msg.linear.z,yaw_rate=msg.angular.z)  
 
    def cmd_vel_enu_callback(self, msg):
        self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
        if self.hover_flag == 0:
            self.coordinate_frame = 1
            self.motion_type = 1
            self.target_motion = self.construct_target(vx=msg.linear.x,vy=msg.linear.y,vz=msg.linear.z,yaw_rate=msg.angular.z)    

    def cmd_accel_flu_callback(self, msg):
        self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
        if self.hover_flag == 0:
            self.coordinate_frame = 8
            self.motion_type = 2
            self.target_motion = self.construct_target(ax=msg.linear.x,ay=msg.linear.y,az=msg.linear.z,yaw_rate=msg.angular.z)    
            
    def cmd_accel_enu_callback(self, msg):
        self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
        if self.hover_flag == 0:
            self.coordinate_frame = 1 
            self.motion_type = 2
            self.target_motion = self.construct_target(ax=msg.linear.x,ay=msg.linear.y,az=msg.linear.z,yaw_rate=msg.angular.z)    
            
    def hover_state_transition(self,x,y,z,w):
        if abs(x) > 0.02 or abs(y)  > 0.02 or abs(z)  > 0.02 or abs(w)  > 0.005:
            self.hover_flag = 0
            self.flight_mode = 'OFFBOARD'
        elif not self.flight_mode == "HOVER":
            self.hover_flag = 1
            self.flight_mode = 'HOVER'
            self.hover()
    def cmd_callback(self, msg):
        if msg.data == self.last_cmd or msg.data == '' or msg.data == 'stop controlling':
            return

        elif msg.data == 'ARM':
            self.arm_state =self.arm()
            print(self.vehicle_type+'_'+self.vehicle_id+": Armed "+str(self.arm_state))

        elif msg.data == 'DISARM':
            self.arm_state = not self.disarm()
            print(self.vehicle_type+'_'+self.vehicle_id+": Armed "+str(self.arm_state))

        elif msg.data[:-1] == "mission" and not msg.data == self.mission:
            self.mission = msg.data
            print(self.vehicle_type+'_'+self.vehicle_id+": "+msg.data)

        else:
            self.flight_mode = msg.data
            self.flight_mode_switch()

        self.last_cmd = msg.data

    def q2yaw(self, q):
        if isinstance(q, Quaternion):
            rotate_z_rad = q.yaw_pitch_roll[0]
        else:
            q_ = Quaternion(q.w, q.x, q.y, q.z)
            rotate_z_rad = q_.yaw_pitch_roll[0]

        return rotate_z_rad
    
    def arm(self):
        if self.armService(True):
            return True
        else:
            print(self.vehicle_type+'_'+self.vehicle_id+": arming failed!")
            return False

    def disarm(self):
        if self.armService(False):
            return True
        else:
            print(self.vehicle_type+'_'+self.vehicle_id+": disarming failed!")
            return False

    def hover(self):
        self.coordinate_frame = 1
        self.motion_type = 0
        self.target_motion = self.construct_target(x=self.current_position.x,y=self.current_position.y,z=self.current_position.z,yaw=self.current_yaw)
        print(self.vehicle_type+'_'+self.vehicle_id+":"+self.flight_mode)

    def flight_mode_switch(self):
        if self.flight_mode == 'HOVER':
            self.hover_flag = 1
            self.hover()
        elif self.flightModeService(custom_mode=self.flight_mode):
            print(self.vehicle_type+'_'+self.vehicle_id+": "+self.flight_mode)
            return True
        else:
            print(self.vehicle_type+'_'+self.vehicle_id+": "+self.flight_mode+"failed")
            return False

if __name__ == '__main__':
    communication = Communication(sys.argv[1],sys.argv[2])
    communication.start()

库函数

import rospy
from mavros_msgs.msg import PositionTarget
from mavros_msgs.srv import CommandBool, SetMode
from geometry_msgs.msg import PoseStamped, Pose, Twist
from std_msgs.msg import String
from pyquaternion import Quaternion
import sys
  • pyquaternion是Python里面计算四元数的一个库,你可以把ta理解为像numpy一样的计算工具。这里面的Quaternion,相关的用法是Quaternion(w, x, y, z),参数可以是实数也可以是字符串,通过指定4个实数标量元素来创建四元数。
  • 4个话题msg,2个服务srv,后面定义话题和服务使用。

启动communication节点

rospy.init_node(sys.argv[1]+'_'+sys.argv[2]+"_communication")
rate = rospy.Rate(30)

传入的参数作为前缀区分多机时的通讯节点

Communication类中的init构造


    def __init__(self, vehicle_type, vehicle_id):
        
        self.vehicle_type = vehicle_type
        self.vehicle_id = vehicle_id
        self.current_position = None
        self.current_yaw = 0
        self.hover_flag = 0
        self.target_motion = PositionTarget()
        self.arm_state = False
        self.motion_type = 0
        self.flight_mode = None
        self.mission = None
        self.last_cmd = None
            
        '''
        ros subscribers
        '''
        self.local_pose_sub = rospy.Subscriber(self.vehicle_type+'_'+self.vehicle_id+"/mavros/local_position/pose", PoseStamped, self.local_pose_callback,queue_size=1)
        self.cmd_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd",String,self.cmd_callback,queue_size=3)
        self.cmd_pose_flu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_pose_flu", Pose, self.cmd_pose_flu_callback,queue_size=1)
        self.cmd_pose_enu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_pose_enu", Pose, self.cmd_pose_enu_callback,queue_size=1)
        self.cmd_vel_flu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_vel_flu", Twist, self.cmd_vel_flu_callback,queue_size=1)
        self.cmd_vel_enu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_vel_enu", Twist, self.cmd_vel_enu_callback,queue_size=1)
        self.cmd_accel_flu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_accel_flu", Twist, self.cmd_accel_flu_callback,queue_size=1)
        self.cmd_accel_enu_sub = rospy.Subscriber("/xtdrone/"+self.vehicle_type+'_'+self.vehicle_id+"/cmd_accel_enu", Twist, self.cmd_accel_enu_callback,queue_size=1)
            
        ''' 
        ros publishers
        '''
        self.target_motion_pub = rospy.Publisher(self.vehicle_type+'_'+self.vehicle_id+"/mavros/setpoint_raw/local", PositionTarget, queue_size=1)

        '''
        ros services
        '''
        self.armService = rospy.ServiceProxy(self.vehicle_type+'_'+self.vehicle_id+"/mavros/cmd/arming", CommandBool)
        self.flightModeService = rospy.ServiceProxy(self.vehicle_type+'_'+self.vehicle_id+"/mavros/set_mode", SetMode)

        print(self.vehicle_type+'_'+self.vehicle_id+": "+"communication initialized")
  • 订阅的话题有mavros发布的无人机的位置,外部程序发布的状态命令,位置命令,速度命令和加速度命令。
  • 注意:这里面的flu代表车身坐标系—前-左-天坐标(自我为中心:The Vehicle Frame —Front-Left-Up,FLU);enu代表局部坐标系—东-北-天坐标(看地球的东西南北:The Local Frame – East-North-Up,ENU)
  • 发布的话题为定位目标,由外部命令得到。
  • 设置的服务有无人机解锁与上锁,无人机飞行模式。
  • 最后,当初始化完毕后,输出:机型+飞机编号+communication initialized。表示初始化完毕了。

回调函数

def local_pose_callback(self, msg):
    self.current_position = msg.pose.position
    self.current_yaw = self.q2yaw(msg.pose.orientation)

运用q2yaw函数进行变换,将四元数变为欧拉角。

def cmd_pose_flu_callback(self, msg):
    self.coordinate_frame = 9
    self.motion_type = 0
    yaw = self.q2yaw(msg.orientation)
    self.target_motion = self.construct_target(x=msg.position.x,y=msg.position.y,z=msg.position.z,yaw=yaw)
    
def cmd_pose_enu_callback(self, msg):
    self.coordinate_frame = 1
    self.motion_type = 0
    yaw = self.q2yaw(msg.orientation)
    self.target_motion = self.construct_target(x=msg.position.x,y=msg.position.y,z=msg.position.z,yaw=yaw)
    
def cmd_vel_flu_callback(self, msg):
    self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
    if self.hover_flag == 0:
        self.coordinate_frame = 8
        self.motion_type = 1
        self.target_motion = self.construct_target(vx=msg.linear.x,vy=msg.linear.y,vz=msg.linear.z,yaw_rate=msg.angular.z)  
 
def cmd_vel_enu_callback(self, msg):
    self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
    if self.hover_flag == 0:
        self.coordinate_frame = 1
        self.motion_type = 1
        self.target_motion = self.construct_target(vx=msg.linear.x,vy=msg.linear.y,vz=msg.linear.z,yaw_rate=msg.angular.z)    

def cmd_accel_flu_callback(self, msg):
    self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
    if self.hover_flag == 0:
        self.coordinate_frame = 8
        self.motion_type = 2
        self.target_motion = self.construct_target(vx=msg.linear.x,vy=msg.linear.y,vz=msg.linear.z,yaw_rate=msg.angular.z)   
def cmd_accel_enu_callback(self, msg):
    self.hover_state_transition(msg.linear.x, msg.linear.y, msg.linear.z, msg.angular.z)
    if self.hover_flag == 0:
        self.coordinate_frame = 1 
        self.motion_type = 2
        self.target_motion = 	   self.construct_target(ax=msg.linear.x,ay=msg.linear.y,az=msg.linear.z,yaw_rate=msg.angular.z)  

以上这几个回调函数主要用到两个函数hover_state_transition函数(悬停状态转换)和construct_target函数(构建目标),首先解释hover_state_transition函数

def hover_state_transition(self,x,y,z,w):
        if abs(x) > 0.02 or abs(y)  > 0.02 or abs(z)  > 0.02 or abs(w)  > 0.005:
            self.hover_flag = 0
            self.flight_mode = 'OFFBOARD'
        elif not self.flight_mode == "HOVER":
            self.hover_flag = 1
            self.flight_mode = 'HOVER'
            self.hover()

这个函数用于悬停状态的转换,当变量x、y、z绝对值大于0.02或w绝对值大于0.005时,转换为OFFBOARD离线模式,当不小于于此值时设置为HOVER悬停模式。
接下来解释construct_target函数

def construct_target(self, x=0, y=0, z=0, vx=0, vy=0, vz=0, afx=0, afy=0, afz=0, yaw=0, yaw_rate=0):
        target_raw_pose = PositionTarget()
        target_raw_pose.coordinate_frame = self.coordinate_frame
        
        target_raw_pose.position.x = x
        target_raw_pose.position.y = y
        target_raw_pose.position.z = z

        target_raw_pose.velocity.x = vx
        target_raw_pose.velocity.y = vy
        target_raw_pose.velocity.z = vz
        
        target_raw_pose.acceleration_or_force.x = afx
        target_raw_pose.acceleration_or_force.y = afy
        target_raw_pose.acceleration_or_force.z = afz

        target_raw_pose.yaw = yaw
        target_raw_pose.yaw_rate = yaw_rate

        if(self.motion_type == 0):
            target_raw_pose.type_mask = PositionTarget.IGNORE_VX + PositionTarget.IGNORE_VY + PositionTarget.IGNORE_VZ \
                            + PositionTarget.IGNORE_AFX + PositionTarget.IGNORE_AFY + PositionTarget.IGNORE_AFZ \
                            + PositionTarget.IGNORE_YAW_RATE
        if(self.motion_type == 1):
            target_raw_pose.type_mask = PositionTarget.IGNORE_PX + PositionTarget.IGNORE_PY + PositionTarget.IGNORE_PZ \
                            + PositionTarget.IGNORE_AFX + PositionTarget.IGNORE_AFY + PositionTarget.IGNORE_AFZ \
                            + PositionTarget.IGNORE_YAW
        if(self.motion_type == 2):
            target_raw_pose.type_mask = PositionTarget.IGNORE_PX + PositionTarget.IGNORE_PY + PositionTarget.IGNORE_PZ \
                            + PositionTarget.IGNORE_VX + PositionTarget.IGNORE_VY + PositionTarget.IGNORE_VZ \
                            + PositionTarget.IGNORE_YAW

        return target_raw_pose

主要通过此函数将订阅的命令话题数据转化为发布话题数据。了解此函数需先认识PositionTarget消息类型

# Message for SET_POSITION_TARGET_LOCAL_NED
#
# Some complex system requires all feautures that mavlink
# message provide. See issue #402.
 
std_msgs/Header header
 
uint8 coordinate_frame  #坐标系选择
uint8 FRAME_LOCAL_NED = 1
uint8 FRAME_LOCAL_OFFSET_NED = 7
uint8 FRAME_BODY_NED = 8
uint8 FRAME_BODY_OFFSET_NED = 9
 
uint16 type_mask  #表示要控制变量的忽略码字。
uint16 IGNORE_PX = 1	# Position ignore flags
uint16 IGNORE_PY = 2
uint16 IGNORE_PZ = 4
uint16 IGNORE_VX = 8	# Velocity vector ignore flags
uint16 IGNORE_VY = 16
uint16 IGNORE_VZ = 32
uint16 IGNORE_AFX = 64	# Acceleration/Force vector ignore flags
uint16 IGNORE_AFY = 128
uint16 IGNORE_AFZ = 256
uint16 FORCE = 512	# Force in af vector flag
uint16 IGNORE_YAW = 1024
uint16 IGNORE_YAW_RATE = 2048
# 共12位,如果要忽略多位,只需要将对应的码相加即可。
# 如速度控制的码字应该是111,111,000,111等于2*2048-1-8-16-32=4039。
# 速度控制加上偏航角控制应该是:101,111,000,111等于3015
# 位置控制的码字应该是111,111,111,000,等于4088.
geometry_msgs/Point position # 位置
geometry_msgs/Vector3 velocity # 线速度
geometry_msgs/Vector3 acceleration_or_force # 线加速度
float32 yaw # 角速度
float32 yaw_rate # 角加速度

construct_target函数将订阅到的命令数据转换为PositionTarget类型的消息发布出去。从而实现对无人机位置,速度,加速度的控制。

def cmd_callback(self, msg):
        if msg.data == self.last_cmd or msg.data == '' or msg.data == 'stop controlling':
            return

        elif msg.data == 'ARM':
            self.arm_state =self.arm()
            print(self.vehicle_type+'_'+self.vehicle_id+": Armed "+str(self.arm_state))

        elif msg.data == 'DISARM':
            self.arm_state = not self.disarm()
            print(self.vehicle_type+'_'+self.vehicle_id+": Armed "+str(self.arm_state))

        elif msg.data[:-1] == "mission" and not msg.data == self.mission:
            self.mission = msg.data
            print(self.vehicle_type+'_'+self.vehicle_id+": "+msg.data)

        else:
            self.flight_mode = msg.data
            self.flight_mode_switch()

        self.last_cmd = msg.data

cmd_callback函数主要用于设置无人机状态,以下为设置各个状态的函数

def arm(self):
        if self.armService(True):
            return True
        else:
            print(self.vehicle_type+'_'+self.vehicle_id+": arming failed!")
            return False
# 通过设置服务设置无人机解锁
def disarm(self):
        if self.armService(False):
            return True
        else:
            print(self.vehicle_type+'_'+self.vehicle_id+": disarming failed!")
            return False
# 通过设置服务设置无人机上锁
def hover(self):
        self.coordinate_frame = 1
        self.motion_type = 0
        self.target_motion = self.construct_target(x=self.current_position.x,y=self.current_position.y,z=self.current_position.z,yaw=self.current_yaw)
        print(self.vehicle_type+'_'+self.vehicle_id+":"+self.flight_mode)
# 设置无人机悬停在上次位置
    def flight_mode_switch(self):
        if self.flight_mode == 'HOVER':
            self.hover_flag = 1
            self.hover()
        elif self.flightModeService(custom_mode=self.flight_mode):
            print(self.vehicle_type+'_'+self.vehicle_id+": "+self.flight_mode)
            return True
        else:
            print(self.vehicle_type+'_'+self.vehicle_id+": "+self.flight_mode+"failed")
            return False
# 通过设置服务更改无人机飞行模式。

start函数

循环发布定位目标消息。

def start(self):
        '''
        main ROS thread
        '''
        while not rospy.is_shutdown():
            self.target_motion_pub.publish(self.target_motion)
            rate.sleep()

参考资料
程序来源
CSDN学习参考

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

无人机仿真XTDrone学习六:XTDrone键盘控制无人机multirotor_communication.py程序分析三 的相关文章

  • c学习--不同c文件中的同名全局变量及同名函数53

    如果在不同的c文件中定义了同名的全局变量 xff0c 则它们会占用相同的内存空间 xff0c 而且编译链接时不会报错 xff01 这可以参考全局变量的内存初始化顺序 对于局部变量而言 xff0c 内存分配的顺序和代码的顺序是一样的 全局变量
  • 基于STM32的FreeRTOS学习之任务基础知识(六)

    记录一下 xff0c 方便以后翻阅 RTOS系统的核心是任务管理 xff0c 初学RTOS系统必须先掌握任务的创建 删除 挂起和恢复等操作 1 什么是多任务系统 玩裸机一般都是在main函数里用while 1 做一个死循环完成所有处理 xf
  • git 推送出现 “fatal: The remote end hung up unexpectedly“ 解决方案

    https blog csdn net qq 41241767 article details 98181952 git 推送出现 34 fatal The remote end hung up unexpectedly 34 解决方案 h
  • 操作系统的设计指导思想——主奴机制

    在学习操作系统的过程中我们会发现一个问题 xff1a 应用程序是应用程序 xff0c 操作系统也是程序 xff0c 操作系统程序凭什么能对应用程序进行组织 管理和协调而不受应用程序损害呢 xff1f 我们认为凭的是特权机制 要想让操作系统做
  • VScode如何配置Git

    注意 xff1a 食用本篇博客的前提是你已经安装好了Git xff0c 并且也有一定的Git基础 因为有些git中比较常用的功能我会略过 第一步 xff1a 配置Git环境变量 右键 我的电脑 xff0c 选择 属性 xff0c 在弹出的对
  • FMC/FSMC/EXMC总线NORFlash/PSRAM接口(异步-复用-不突发/同步-复用-突发)

    请勿转载 目录 1 简介 1 1 框图 1 2 接口定义 1 3 读写时序图 时序配置参数 1 4 PSRAM控制器异步工作模式分类 1 5 PSRAM寄存器配置 1 5 1 控制寄存器BCR 1 5 2 片选时序寄存器BTR 1 5 3
  • 开平方_复数有效值+角度的verilog代码

    1 逐位比较法 二进制 FPGA篇 xff08 一 xff09 基于verilog的定点开方运算 1 逐次逼近算法 该篇文章中有详细描述 假设被开方数rad i 7 0 xff0c 则结果qout 3 0 位宽为4位 xff0c 从最高位到
  • GOOSE报文分析_详解GOOSE服务

    https www cnblogs com software4y p 10017602 html http blog sina com cn s blog af8298410102wnvm html https www cnblogs co
  • 循环冗余校验(CRC)之verilog实现

    有一个网站在这一方面做的特别好 xff0c 直接生成代码 链接 xff1a http www easics com webtools crctool 循环冗余校验 xff0c 也称为CRC检验 xff0c 这是一个很常见的 xff0c 很成
  • 从原理上解释什么是DDR的ZQ校准?

    前言 首先我们我们看下下图的电路 xff0c 在DDR的电路中通常有ZQ部分的电路 xff0c 外接1 高精度的240ohm电阻 xff0c 那么这个240ohm电阻究竟是做什么用的呢 xff1f 很多做了硬件或者驱动开发很多年的工程师仍然
  • 串行数据异步动态相位采样处理iodelay-iserdes应用+CDR数据恢复方案

    目录 一 用iserdes的LVDS视频接口 二 LVDS 4倍异步过采样 ISERDES2 三 8倍过采样 CDR数据恢复 Select IO 替代 RocketIO 典型应用SD SDI 四 4倍过采样 CDR数据恢复 一 用iserd
  • 接收灵敏度dbm与W

    一 基本概念 xff1a 接收灵敏度 官方概念 xff1a 接收机能够识别到的 最低的电磁波能量 单位也是dBm 解读 xff1a 接收灵敏度 xff0c 就是你的耳朵能听到的最小的声音 耳朵灵敏度高的 xff0c 能够听到很远的声音 例如
  • 三段式过流保护、差动保护

    1 基本原理 供电系统中的线路 设备等故障 xff0c 会产生短路电流 短路电流比线路正常工作时大很多 通过电流互感器测量这个电流值 xff0c 和电流值的持续时间 xff0c 达到整定值时输出跳闸信号 xff0c 这个就是过电流保护的基本
  • Unexpandable Clocks不可扩展时钟 UG903

    同源时钟可能同步 xff0c 可能异步 xff1f 同源时钟由同一个PLL MMCM产生 xff0c 相位固定 xff0c 能否产生小数倍关系 xff1f 不可扩展时钟能否归类到异步时钟 xff1f 不可扩展时钟是指时钟引擎无法在1000个
  • allegro 尺寸标注操作未到板边的处理

    1 进入尺寸标注 2 右击选择线性 xff0c parameters中可以改参数 xff0c 默认即可 3 打开尺寸层 xff0c 点击板边框 如果有圆弧没有标注到板边 xff0c 可以在右侧find中关闭其它项 xff0c 点击两个板边标
  • 安装boost

    安装boost 从官网下载并解压到适当位置 Boost网站 在解压后的目录中找到 bootstrap bat点击运行 xff0c 并等待结束 这时会出现b2 exe文件 xff0c 点击运行 xff0c 耐心等待结束 xff08 安装后产生
  • 基于PCIe的NVMe协议在FPGA中实现方法

    NVMe协议是工作在PCIE的最上层协议层的 xff0c 故需要先搞清楚PCIE 本文基于Xilinx的UltraScale 43 xff0c 开发工具为Vivado2021 2 学习中以spec为主 xff0c 其它资料辅助参考 重点介绍
  • PX4地面参数配置

    1 空速计 在不使用空速计的情况下 xff0c 配置CBRK AIRSPD CHK参数失能传感器 xff0c waining消失 2 数传部分 配置SER TEL1 BAUD的波特率与数传一致 xff0c 在地面站选择数传端口进行连接 xf
  • 企业微信公众账号自定义应用模块中撤回历史消息的方法

    企业微信 xff0c 公众账号自定义应用模块中撤回历史消息的方法 注意 xff1a 此方法适用于撤回超过24小时的历史消息 下载这个工具 xff1a postman xff1a http www downza cn soft 205171
  • windows的BAT或者linux的VI下批量更改替换文件名的脚本

    windows 的BAT 或者linux 的VI 下批量更改替换文件名的脚本 本来离开写脚本有些日子了 xff0c 倒是现在有些文件处理或者EXCEL 工作簿要处理的话 xff0c 还是会用简化流程来处理 脚本函数则帮我解决了很多麻烦事 昨

随机推荐

  • 那些年,我们一起读过的《JAVA与模式》

    那些年 xff0c 我们一起读过的 JAVA与模式 刚上大二 xff0c 买回来那一本厚厚的 JAVA与模式 时 xff0c 我还很不舍得 xff0c 这价格 xff0c 可以供一周的生活费了 既然买了 xff0c 就得读一读吧 先说说阎宏
  • 室内定位技术及机场方案建议

    室内定位技术发展现状 在1996年左右 xff0c 美国联邦通信委员会 xff08 FCC xff09 要求移动运营商为移动电话用户提供E 911 xff08 紧急救援 xff09 服务 1999年 xff0c FCC又对定位精度做出新的要
  • 如何让ActiveXObject( "Microsoft.XmlDom ")对象在非IE浏览器下显示数据?firefox(火狐)

    在IE浏览器下 xff0c xmlDom对象一般这样被定义 xff1a var xmlDom 61 new ActiveXObject 34 Microsoft XMLDOM 34 为了兼容Firefox xff0c 需要修改为 xff1a
  • BIM+GIS建设与运维管理工作建议

    背景 xff1a BIM 43 GIS项目的建设意见 xff0c 就弱电的建设和运维方向提出相关需求 xff1b 在BIM模型建设时期 xff0c 面向弱电专业的建设建议 参考行业规范 xff1a 在机场工程项目的建设阶段 xff0c 各参
  • 修改svn默认端口

    Subversion有两种不同的配置方式 xff0c 一种基于它自带的轻量级服务器svnserve xff0c 一种基于非常流行的Web服务器Apache 根据不同的配置方式 xff0c Subversion使用不同的端口对外提供服务 基于
  • 项目、系统开发中的需求分析说明书和需求规格说明书的区别

    项目组成员在针对要开发的系统做需求调研后 xff0c 就要编写对应的需求说明书 作为软件工程师 xff0c 你就得知道需求分析说明书和需求规格说明书的区别 xff0c 以期在正确的时候编写正确的需求文档 两者有何不同 xff1a xff08
  • 全景视频拼接的关键技术与步骤

    全景视频拼接是一种利用实景图像组成全景空间的技术 xff0c 它将多幅图像拼接成一幅大尺度图像或360度全景图 全景视频技术涉及到计算机视觉 计算机图形学 数字图像处理以及一些数学工具等技术 全景拼接基本步骤主要包括 xff1a 摄像机的标
  • Ubuntu18.04+ROS Realsense的安装与使用

    文章目录 前言一 安装软件包与librealsense1 内核检查2 Installing the packages 2022 11 21更新 xff1a 在换了ubuntu20 04 xff08 带有 xff09 5 15的内核报错后 x
  • C/C++内存管理详解[转载]

    我觉得这是一篇很不错的文章 xff0c 对C和C 43 43 的程序员来说 xff0c 很有实用价值 xff0c 故推荐给大家 作者 xff1a PingPong 文档来源 xff1a CSDN 伟大的Bill Gates 曾经失言 xff
  • 项目启动会应该注意的几点

    摘要 xff1a 开个好头 xff0c 万事不难 项目启动会作为项目建设生命周期的开始 xff0c 其意义和难度不言而喻 作为项目管理办公室的负责人 xff0c 需要特别重视项目启动会的召开 xff0c 杜绝走过场 xff0c 避免虽然知道
  • 飞机的航班代码/航班号码的编号规则

    以下内容来源于网络 xff0c 并整理而得 一 国内航班 中国国内航班号的编号规则 xff1a 航空公司的两字代码 43 4位数字 其中 xff0c 后面四位数字的第一位代表航空公司的基地所在地区 第二位代表航班基地外终点所在地区 xff0
  • 机场生产运行数据统计指标-第四篇-机场运行保障类

    机场运行保障类 1 民航航班正常统计 1 1 统计说明 xff08 1 xff09 统计范围的相关说明 xff1a 1 民航航班正常统计范围 xff1a 国内外运输航空公司执行的客货运航班 xff0c 包括正班 加班 包机 港澳台地区及国际
  • STM32CubeMAX入门篇

    要求使用单片机STM32F407IGT6 1 时钟配置 STM32F407外部高速晶振为25MHz xff0c 分别连接到PH0和PH1引脚 2 SWD配置 STM32F407仿真接口SWD分别连接到PA13和PA14引脚 xff01 开始
  • 无人机仿真XTDrone学习一:Mavros基础知识与作用

    XTDrone等无人机仿真平台 xff0c 利用ROS 43 Gazbo 43 PX4进行SITL xff08 软件在环仿真 xff09 xff0c 主要利用PX4飞控的offboard模式 xff0c 在此模式下上位机程序发布期望运动 x
  • 无人机仿真XTDrone学习二:常用的mavros消息类型

    mavros用于无人机通信 xff0c 可以将飞控与主控的信息进行交换 本次记录常用的mavros消息类型 官方Wiki最正确 xff0c 如有疑问首先查阅Wiki mavros wiki CSDN参考 常用话题 数传 用于查看数传状态 x
  • 无人机仿真XTDrone学习三:MAVRos功能包在offboard模式控制例程

    本教程介绍了使用 Gazbo SITL 中模拟的四轴飞行器 Offboard 控制缓慢起飞到2米的高度 61 61 注意 xff1a 61 61 使用 Offboard 模式来控制无人机有危险性的 如果你是在一个真正的实物平台上进行试验 x
  • 无人机仿真XTDrone学习四:XTDrone键盘控制无人机程序分析(MAVRos)一

    在XTDrone安装完成后 xff0c 运行一个键盘控制无人机程序测试XTDrone安装是否存在问题 通过分析该例程 xff0c 理解ROS对无人机的控制方法与控制过程 XTDrone键盘控制无人机例程仿真 XTDrone键盘控制无人机例程
  • 无人机仿真XTDrone学习五:XTDrone键盘控制无人机indoor1.launch程序分析二

    launch程序如下 这个文件启动了Gazebo仿真环境 xff0c 配置MAVROS功能包和PX4 SITL功能包 span class token prolog lt xml version 61 34 1 0 34 gt span s
  • 接收机灵敏度的计算公式推导和分析

    接收机灵敏度定义的接收机能够接收到的并且还能正常工作的最低电平强度 接收机灵敏度跟很多东西有关 xff0c 如噪声系数 信号带宽 解调信噪比等 xff0c 灵敏度一般来说越高 xff08 数值越低 xff09 xff0c 说明其接收微弱信号
  • 无人机仿真XTDrone学习六:XTDrone键盘控制无人机multirotor_communication.py程序分析三

    multirotor communication py程序 这个程序是实现对无人机控制的主要程序 xff0c 需要重点分析 可以实现对无人机的位置 xff0c 速度 xff0c 加速度的控制 主要节点 xff1a sys span clas