@@ -93,7 +93,7 @@ def cmd_parachute(self, args):
9393 cmd = cmds [args [0 ]]
9494 self .master .mav .command_long_send (
9595 self .settings .target_system , # target_system
96- 0 , # target_component
96+ self . settings . target_component , # target_component
9797 mavutil .mavlink .MAV_CMD_DO_PARACHUTE ,
9898 0 ,
9999 cmd ,
@@ -105,7 +105,7 @@ def cmd_camctrlmsg(self, args):
105105 print ("Sent DIGICAM_CONFIGURE CMD_LONG" )
106106 self .master .mav .command_long_send (
107107 self .settings .target_system , # target_system
108- 0 , # target_component
108+ self . settings . target_component , # target_component
109109 mavutil .mavlink .MAV_CMD_DO_DIGICAM_CONFIGURE , # command
110110 0 , # confirmation
111111 10 , # param1
@@ -128,7 +128,7 @@ def cmd_cammsg(self, args):
128128 print ("Sent DIGICAM_CONTROL CMD_LONG" )
129129 self .master .mav .command_long_send (
130130 self .settings .target_system , # target_system
131- 0 , # target_component
131+ self . settings . target_component , # target_component
132132 mavutil .mavlink .MAV_CMD_DO_DIGICAM_CONTROL , # command
133133 0 , # confirmation
134134 params [0 ], # param1
@@ -157,7 +157,7 @@ def cmd_engine(self, args):
157157
158158 self .master .mav .command_long_send (
159159 self .settings .target_system , # target_system
160- 0 , # target_component
160+ self . settings . target_component , # target_component
161161 mavutil .mavlink .MAV_CMD_DO_ENGINE_CONTROL , # command
162162 0 , # confirmation
163163 params [0 ], # param1
@@ -174,7 +174,7 @@ def cmd_cammsg_old(self, args):
174174 print ("Sent old DIGICAM_CONTROL" )
175175 self .master .mav .digicam_control_send (
176176 self .settings .target_system , # target_system
177- 0 , # target_component
177+ self . settings . target_component , # target_component
178178 0 , 0 , 0 , 0 , 1 , 0 , 0 , 0 )
179179
180180 def cmd_do_change_speed (self , args ):
@@ -237,7 +237,7 @@ def cmd_velocity(self, args):
237237 self .master .mav .set_position_target_local_ned_send (
238238 0 , # system time in milliseconds
239239 self .settings .target_system , # target system
240- 0 , # target component
240+ self . settings . target_component , # target component
241241 8 , # coordinate frame MAV_FRAME_BODY_NED
242242 4039 , # type mask (vel only)
243243 0 , 0 , 0 , # position x,y,z
@@ -259,7 +259,7 @@ def cmd_position(self, args):
259259 self .master .mav .set_position_target_local_ned_send (
260260 0 , # system time in milliseconds
261261 self .settings .target_system , # target system
262- 0 , # target component
262+ self . settings . target_component , # target component
263263 8 , # coordinate frame MAV_FRAME_BODY_NED
264264 3576 , # type mask (pos only)
265265 x_m , y_m , z_m , # position x,y,z
@@ -314,7 +314,7 @@ def cmd_attitude(self, args):
314314 self .master .mav .set_attitude_target_send (
315315 0 , # system time in milliseconds
316316 self .settings .target_system , # target system
317- 0 , # target component
317+ self . settings . target_component , # target component
318318 mask , # type mask
319319 att_target , # quaternion attitude
320320 math .radians (roll_rate ), # body roll rate
@@ -347,7 +347,7 @@ def cmd_posvel(self, args):
347347 self .master .mav .set_position_target_global_int_send (
348348 0 , # system time in ms
349349 self .settings .target_system , # target system
350- 0 , # target component
350+ self . settings . target_component , # target component
351351 mavutil .mavlink .MAV_FRAME_GLOBAL_RELATIVE_ALT_INT ,
352352 ignoremask , # ignore
353353 int (latlon [0 ] * 1e7 ),
0 commit comments