BlueROV2 lamp and camera tilt does not work with RC input

Hello,

I am trying to control the BlueROV2 manually by pymavlink.

I managed to control the thruster by RC input.

However, when I am trying to control the camera tile and the lamp in the same way as the thruster control, there is no response.

I tried the code

set_rc_channel_pwm(8, 1900)

and

set_rc_channel_pwm(7, 1900)

I also tried ’ Control Camera Gimbal’ in the manual ‘http://www.ardusub.com/developers/pymavlink.html’
still, nothing happened.

I check the Qgroundcontrol, where the channel of the lamp is 7 and camera tilt is 8.

But when I moved to the camera section, the camera mount tilt speed is zero at the left.

It also gave me warning in the yellow box.


If I manually change the camera tilt speed to somewhere, after I click the camera icon on the left side next time, it will be zero again.

I have tried to control the camera tilt angle last year and I did not change and hardware connection.

I was wondering if you could help me with the camera tilt and light problem.

I really appreciate your help!

RC Inputs/Outputs

This seems like you’ve got your RC Inputs and Outputs confused. The Lights and Camera pages on QGC are specifying the RC Output (servo) channels (the physical Pixhawk ports that things are plugged into), which by default are 7 (lights 1) and 8 (camera tilt) respectively. The RC Inputs are instead to do with some of the control commands related to the joystick inputs, for which the defaults are 8 (camera tilt) and 9 (lights 1 level).

Camera Tilt Sweep with Speed

In saying that, the ‘camera tilt’ functionality there is a bit misleading (and poorly documented). Our Send RC (Joystick) example sets the camera tilt RC Input channel (8) to 1900 pwm, and specifies that it sets camera tilt to 45^{\text{o}} with full speed. I’ve just spent some time figuring out what that means, and apparently the ‘pwm’ value that gets set here determines the speed for a sweep from the current tilt angle to \pm45^{\text{o}}. The way that works is that 1500 is the ‘zero’ speed setting (do nothing, go nowhere), and 1100 is ‘full speed to -45^\text{o}’, while 1900 is ‘full speed to +45^\text{o}’. As some pointers:

  • Anything above 1500 will always go all the way to +45^\text{o}, but 1700 will do so at seemingly half the speed that 1900 would. The same applies for the opposite direction (1100 is about double the speed of 1300, and 1499 is incredibly slow).
  • If the camera is already at one of the extremes then additional signals to the same side do nothing (e.g. if the tilt angle is currently -45^\text{o} then rc_channels_override_send(8, 1100) will go full-speed to where it already is, so it won’t move).
  • The latest command is the one that is acted on, so if you do one call for rc_channels_override_send(8, 1300) and then when it’s partway there you do another call for rc_channels_override_send(8, 1100) then it will change to full speed the rest of the way to -45^\text{o}.
  • you may need to run the following command between your wait_heartbeat and your first
    set_rc_channel_pwm call, to configure the mount controls to RC mode:
    master.mav.mount_configure_send(
        master.target_system,
        master.target_component, 
        mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING, 
        0, 0, 0)
  • I’m not sure how ‘full speed’ is set/determined, but it’s not the full speed of the servo (see below)

Setting Camera Mount Angle

It’s also possible to directly set the camera mount tilt angle instead of doing a smooth camera sweep to one of the extents. That’s what our Control Camera Gimbal example does, and any tilt angle you set there is moved to as fast as the servo can, which is considerably faster than the set_rc_channel_pwm tilt sweep, but that also means you can’t really see any image details in the brief period where the servo is moving (the frames get too much motion blur).

There’s also a slightly simpler command for mount control:

master.mav.mount_control_send(
    master.target_system,
    master.target_component,
    tilt, # cdeg, -4500 to 4500
    0, # roll cdeg
    0, # pan cdeg
    0) # save_position (not used)

but if you’ve been using RC control beforehand then you’ll need to explicitly set the camera mount to mavlink mode (instead of RC mode) before the mount_control_send commands will work:

master.mav.mount_configure_send(
    master.target_system,
    master.target_component, 
    mavutil.mavlink.MAV_MOUNT_MODE_MAVLINK_TARGETING, 
    0, 0, 0)

Lights

You can control the lights using either set_rc_channels_pwm(9, pwm), or master.set_servo(7, pwm) assuming your lights are plugged in to MAIN OUT 7 of the Pixhawk. There shouldn’t be requirement to set a mode or anything for either of those approaches - if you have a valid connection to your autopilot they should work.

QGC Error: Missing Parameters

Which versions of QGroundControl and ArduSub are you using? “Missing Parameters” means that some of the parameters QGroundControl is expecting are missing from your installed ArduSub firmware, which is either because your QGroundControl version is very new (includes added parameters that don’t exist in ArduSub), or your ArduSub version is very old (some parameters that did exist have been renamed).

Hello Eliot,

Thank you for your information.

I have managed to control the light by following your instruction.

However, I still cannot move the camera, by either “sweep with speed” or “mount angle”.

For example, in the Control camera Gimbal example, I add the mavlink mode declaration, and run the script, but the camera does not move at all.

I also tried to disarm it before I run the script, but still, the camera did not move.

For the version of QGroundControl, I am not sure how to check the version, but I was in Linux system, and I installed the QGroundControl from the BlueROV website last month.

I was wondering if you could help me with this camera tilt problem?

I really appreciate your help!

Glad to hear it :slight_smile:

That’s unusual - that example works fine on my surface computer. The example in our pymavlink documentation already sets the mode in the look_at function - the mode declaration is only required if you want to use the simpler mount control command I outlined in my last comment.

What happens when you run the script? Can you put a print statement after the master.wait_heartbeat() line to confirm that it successfully makes a connection to the ROV? I expect that’s fine because you were able to control your lights, but still good to check.

Most likely you’re on version 4.0.5 then. You can check by pressing the purple Q button in the top left corner and scrolling down to the bottom of the ‘General’ tab. Note that QGC shouldn’t be open while you’re trying to run your pymavlink code.

Could you please check your ArduSub version in the companion web interface System page (go to http://192.168.2.2:2770/system)? There’s a section at the bottom called “Pixhawk Firmware Update”, and the listed ArduSub version should be 4.0.3. If it’s not please update by pressing the Stable button and waiting for the update to complete.

It may also be worth checking your pymavlink version (e.g. with python3 -m pip show pymavlink assuming you installed it with pip), although if your code isn’t raising exceptions then this most likely isn’t the issue. Mine is 2.4.15.

Hello Eliot,

Thank you for your reply.

It looks like the problem of my ArduSub version. I upgraded it to development version, which is 4.2.0.

Now I upgraded it to stable version, which is 4.0.3, and the camera tilt function works.

Thank you so much for your help.

1 Like

@williangalvani has noticed that in ArduSub 4.2.0 the MNT_TYPE parameter is set to 0 (None) by default, instead of 1 (Servo). It’s possible your camera mount wasn’t working because the mount itself isn’t enabled.

For anyone wanting to use 4.2.0, the parameter value can be set via the QGC Parameters tab, or using pymavlink.