Hi y’all, I am trying guide a blue rov sub to do simple waypoint missions using pymavlink. I am trying to use the set position command to move the ROV, but I have not gotten the motors to spin. Also I am receive position information from the DVL attached to the robot, and sending back to the ROV to update its local and gps position, but I am unsure if the autopilot is receiving these. Do y’all have know what I am doing wrong, or a better way to do it? Also is there a good way to see if the ROV’s computers are receiving the messages I am sending?, Thanks for your help
Here is the code I am using to send the set position command
self.robot.secondary.mav.set_position_target_local_ned_send(
int(1e3 * (time.time() - self.robot.bootTime)), # ms since boot
self.robot.master.target_system,
self.robot.master.target_component,
coordinate_frame=mavutil.mavlink.MAV_FRAME_LOCAL_OFFSET_NED,
type_mask=(
#mavutil.mavlink.POSITION_TARGET_TYPEMASK_X_IGNORE |
#mavutil.mavlink.POSITION_TARGET_TYPEMASK_Y_IGNORE |
#mavutil.mavlink.POSITION_TARGET_TYPEMASK_Z_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_VZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AX_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AY_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_AZ_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_IGNORE |
mavutil.mavlink.POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE),
x=xd, y=yd, z=zd, # (x, y, z) [m] positive is NED
vx=0, vy=0, vz=0, # velocities in NED frame [m/s] (not used)
afx=0, afy=0, afz=0, # accelerations in NED frame [m/s/s]
yaw=0, yaw_rate=0 # heading [rad] and yaw rate [rad/s] N is 0
)
Here is the code I am using to send the position information
self.master.mav.gps_input_send(
self.lib.GetTickCount64(), # Timestamp (micros since boot or Unix epoch)
0, # ID of the GPS for multiple GPS inputs
# Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum).
# All other fields must be provided.
0, # GPS time (milliseconds from start of GPS week)
0, # GPS week number
(mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_VEL_HORIZ |
mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_VEL_VERT |
mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY|
mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_HDOP|
mavutil.mavlink.GPS_INPUT_IGNORE_FLAG_VDOP),
5, # 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
int(self.pos_GPS['lat']*1E7), # Latitude (WGS84), in degrees * 1E7
int(self.pos_GPS['lon']*1E7), # Longitude (WGS84), in degrees * 1E7
0, # Altitude (AMSL, not WGS84), in m (positive for up)
1, # GPS HDOP horizontal dilution of position in m
1, # GPS VDOP vertical dilution of position in m
0, # GPS velocity in m/s in NORTH direction in earth-fixed NED frame
0, # GPS velocity in m/s in EAST direction in earth-fixed NED frame
0, # GPS velocity in m/s in DOWN direction in earth-fixed NED frame
0, # GPS speed accuracy in m/s
0, # GPS horizontal accuracy in m
0, # GPS vertical accuracy in m
20, # Number of satellites visible.
)
self.master.mav.local_position_ned_send(
self.lib.GetTickCount64(),
self.pos['x'],
self.pos['y'],
self.pos['z'],
self.pos['vx'],
self.pos['vy'],
self.pos['vz'],
)