<enum name="MAV_ROI">
<description> The ROI (region of interest) for the vehicle. This can be
be used by the vehicle for camera/vehicle attitude alignment (see
MAV_CMD_NAV_ROI).
</description>
<entry name="MAV_ROI_WPNEXT" value="0"><description>Point toward
next waypoint.</description></entry>
<entry name="MAV_ROI_WPINDEX" value="1"><description>Point toward
given waypoint.</description></entry>
<entry name="MAV_ROI_LOCATION" value="2"><description>Point
toward fixed location.</description></entry>
<entry name="MAV_ROI_TARGET" value="3"><description>Point toward
target of given id.</description></entry>
</enum>
In addition, i have renamed the existing MAV_NAV_ORIENTATION_TARGET to
MAV_NAV_ROI:
<entry name="MAV_CMD_NAV_ROI" value="80">
<description>Sets the region of interest (ROI) for a sensor set or the
vehicle itself. This can then be used by the vehicles control
system to control the vehicle attitude and the attitude of various
devices such as cameras.</description>
<param index="1">Region of intereset mode. (see MAV_ROI enum)</param>
<param index="2">Waypoint index/ target ID. (see MAV_ROI enum)</param>
<param index="3">ROI index (allows a vehicle to manage
multiple ROI's)</param>
<param index="4">Empty</param>
<param index="5">x the location of the fixed ROI (see MAV_FRAME)</param>
<param index="6">y</param>
<param index="7">z</param>
</entry>
Please give me your feedback on this change and let me know if it
meets all of your requirements. You can check out this change using:
git clone git://github.com/pixhawk/mavlink.git -b roi
-James
So the thought is you would send an orientation command and target command separately?
Would I now need to implement a stored list of ROI targets to do orientation?
I would prefer to simply send :
MAV_CMD_DO_ORIENTATION: Yaw_Mode, altitude, lat, lon
The GCS would handle anything more complex such as ROI lists.
Thanks,
Jason
I do agree that we should probably change it to MAV_CMD_DO_ROI as the
message has no condition and executes immediately. In my code I'm
evaluating the proceed condition on a per-message basis, are you
somehow evaluating it on the id range, or is this just a naming issue
with the CMD_DO?
Here is how the command would work for your example message:
mode: MAV_ROI_LOCATION
x,y,z: lat/lon/alt if you use MAV_FRAME_GLOBAL
the rest of the fields wouldn't matter for you
I think the confusing issue here was my wording on the ROI ID, this is
intended to allow your vehicle to have a camera 1, camera 2, turrets,
vehicle attitude etc. If you don't want to use that feature just pass
whatever you like and ignore the field. Another option,as you
suggested, would be to have an enum of commonly used objects.
-James
OK, so let me know exactly how I would receive and parse the following pseudo command:
- Yaw towards a target (while flying) with these coordinates X, Y, Z
It's the last thing for me to finish the beta!
Thanks!
Jason
If that looks good to you let me know and I"ll commit the change to
the roi branch, i'll change the id to be at the end of the current do
cmd's.
if (id==MAV_CMD_DO_SET_ROI && msg.p1 == MAV_ROI_WPNEXT)
{
yawTargetMode = false;
(or however you want to handle it)
MAV_ROI_NONE 0
MAV_ROI_WPNEXT 1
MAV_ROI_WPINDEX 2
MAV_ROI_LOCATION 3
MAV_ROI_TARGET 4
Thanks,
Jason
-James