Giter Site home page Giter Site logo

px4-flow's Introduction

PX4Flow Firmware

Build Status

Gitter

PX4 FLOW is a smart camera processing optical flow directly on the camera module. It is optimized for processing and outputs images only for development purposes. Its main output is a UART or I2C stream of flow measurements at ~400 Hz.

Dev guide / toolchain installation: https://docs.px4.io/master/en/sensor/px4flow.html

For help, run:

make help

To build, run:

  make archives # this needs to be done only once
  make

To flash via the PX4 bootloader (first run this command, then connect the board):

  make upload-usb

By default the px4flow-v1_default is uploaded; to upload a different version, run:

  make <target> upload-usb

Where <target> is one of the px4flow targets listed by make help.

px4-flow's People

Contributors

bkueng avatar bn999 avatar christophtobler avatar dagar avatar de-vri-es avatar drton avatar gcbower avatar jgoppert avatar jhiesey avatar julianoes avatar kevinmehall avatar lorenzmeier avatar mike239x avatar samized avatar tcauchois avatar tpetri avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

px4-flow's Issues

MT9v034 Camera

Dear all,
I have a simple question. Can I change the camera sensor to another one? Since this sensor mt9v034 requires a lens that is pretty large, I want to change it into another smaller camera such as OVA7670, etc. Can I do that?

nan x,y velocities

Hello all,
Recently I flashed by Flow with the latest stable release of the firmware through QGroundControl. This has enabled us to view the camera image from the ros node that is being developed here: http://wiki.ros.org/px4flow_node.

However, after the firmware flash the flow_comp_m_x and flow_comp_m_y values often return a value of nan. Looking through the firmware here I think the only way this could happen is at line 395 of main.c when flow_copmx/y are divided by get_time_between_images() if get_time_between_images() returned 0.

I'm curious if anyone else is getting nan values for velocities and if indeed the problem is in get_time_between_images().

Any advice of where to investigate would be much appreciated.

== comparisons using float numbers

@dominiho Several lines, including this one do float comparisons:

6d584340 (dominiho      2014-10-27 13:27:01 +0100 480)                  if(global_data.param[PARAM_SONAR_FILTERED])

You can fix this by using:

static_cast<int>(global_data.param[PARAM_SONAR_FILTERED] + 0.5f)

What is the resolution that STM32F427 handles?

As we know, the SRAM in F427 is only 256KB, so if it captures the full 640x480 resolution image, the sram cannot store it. Does this pix4flow configures the camera sensor at a lower resolution, say 320x240 or something else?

setup firmware "Beginner"

how do i upload this firmware to the PX4 ?
also i updated the firmware through QGround software and the Ground distance is always zero even the built in Sonar works fine alone
thanks for your help

sonar max range returns zero

I'm coding a flow only position estimator here: https://github.com/jgoppert/Firmware/tree/flow_est_update
I'm using the sonar on the flow for altitude and flow camera for position estimation.

https://github.com/jgoppert/Firmware/blob/flow_est_update/src/examples/flow_position_estimator/FlowPositionEstimator.cpp

I just tested this estimator and the position estimation looks decent, but when I go into auto it climbs continuously because the altitude estimation using the flow sonars returns 0 when the sonar hits max range. I think this is very confusing. I would expect the sonar to return max range when it doesn't get a pulse back. I'm willing to work on this, but I wanted to see if there is any logic with the current code and I don't create some incompatibility with position_estimator_inav @DrTon.

I tested the sonar and noticed that particular angles return 0 even when no object is in view. I'm not sure if this is some kind of major code glitch or a hardware problem on my end.

I'm using the flow over i2c connection and the latest firmware on master for both flow and the fmu.

Extending I2C funcionality patch

I've wrote patch to add following stuff to the I2C;

  1. Reading integral frame by one byte at the time (to save memory on small atmega328 hosts) - send offset+32 then read one byte
  2. Reading px4flow parameters settings - send parameter number +128 then read 4 bytes (float)
  3. Updating px4flow parameters settings - send parameter number +128 and 4 bytes (float)
--- src/modules/flow/i2c.c.orig 2015-08-22 08:54:18 +0300
+++ src/modules/flow/i2c.c  2015-08-27 19:48:53 +0300
@@ -51,9 +51,13 @@
 #include "gyro.h"
 #include "sonar.h"
 #include "main.h"
-
+#include "settings.h"
+#include "usart.h"
+#include "dcmi.h"
+#include "mt9v034.h"
 #include "mavlink_bridge_header.h"
 #include <mavlink.h>
+#include "communication.h"

 /* prototypes */
 void I2C1_EV_IRQHandler(void);
@@ -71,6 +75,8 @@
 uint8_t readout_done_frame1 = 1;
 uint8_t readout_done_frame2 = 1;
 uint8_t stop_accumulation = 0;
+uint8_t regNum;
+float  tmpParam;

 void i2c_init() {

@@ -158,6 +164,7 @@
        //receive address offset
        dataRX = I2C_ReceiveData(I2C1 );
        rxDataIndex++;
+       if (rxDataIndex == 1 && (dataRX < 0x20)) {
        //set Index
        txDataIndex1 = dataRX;
        if (dataRX > I2C_FRAME_SIZE) {
@@ -169,10 +176,82 @@
            //indicate sending
        readout_done_frame1 = 0;
        readout_done_frame2 = 0;
+       } else {
+           // receiving parameter value (0x80+setting number)
+           switch (rxDataIndex) {
+               case 1:
+                   // Just register number or specific element from integral frame
+                   if (dataRX < 0x80) {
+                       regNum = dataRX - 0x20;
+                       readout_done_frame2 = 0;
+                       readout_done_frame1 = 0;
+                   } else {
+                       regNum = dataRX - 0x80;
+                       txDataIndex1 = 0;
+                   }
+                   break;
+               case 2:
+                   // lower byte
+                   *((uint8_t *) &tmpParam) = dataRX;
+                   break;
+               case 3:
+                   *((uint8_t *) &tmpParam + 1) = dataRX;
+                   break;
+               case 4:
+                   *((uint8_t *) &tmpParam + 2) = dataRX;
+                   break;
+               case 5:
+                   *((uint8_t *) &tmpParam + 3) = dataRX;
+                   // higher byte, saving parameter
+                   rxDataIndex = 0;
+                   if (global_data.param_access[regNum] == READ_ONLY)
+                       break;
+                   global_data.param[regNum] = tmpParam;
+                   // copied from communication.c - do stuff for some parameters
+                   switch (regNum) {
+                       case PARAM_SENSOR_POSITION:
+                           set_sensor_position_settings((uint8_t) tmpParam);
+                            mt9v034_context_configuration();
+                            dma_reconfigure();
+                            buffer_reset();
+                           break;
+                       case PARAM_IMAGE_LOW_LIGHT:
+                       case PARAM_IMAGE_ROW_NOISE_CORR:
+                           mt9v034_context_configuration();
+                           dma_reconfigure();
+                           buffer_reset();
+                           break;
+                       case PARAM_GYRO_SENSITIVITY_DPS:
+                           l3gd20_config();
+                           break;
+                   }
+                   break;
+               default:
+                   break;
+           }
+       }
        break;
    }
    case I2C_EVENT_SLAVE_BYTE_TRANSMITTING :
    case I2C_EVENT_SLAVE_BYTE_TRANSMITTED : {
+       // Check if host is asking for parameters, not frames
+       if (dataRX > 0x80) {
+           I2C_SendData(I2C1,
+                   *(((uint8_t *) &global_data.param[regNum]) + txDataIndex1));
+           txDataIndex1++;
+           break;
+       }
+       // Check if host wants specific byte from integral array (+0x20)
+       if (dataRX > 0x20) {
+           I2C_SendData(I2C1,
+                   txDataFrame2[publishedIndexFrame2][regNum]);
+           // If last byte from integral array read - reset accumulation
+           if (regNum >= (I2C_INTEGRAL_FRAME_SIZE-1)) {
+                           readout_done_frame2 = 1;
+                           stop_accumulation = 1;
+           }
+           break;
+       }

        if (txDataIndex1 < (I2C_FRAME_SIZE)) {
            I2C_SendData(I2C1,

Bug in X axis flow output - affects latest master and stable release

I ran a test today using the latest firmware from master, where the quad-copter was supported about 20cm above a table and the lens was focused onto a textured towel placed underneath the camera that could be slid in both the X and Y directions. The towel was slid a sequence of doublets (trying to keep a constant speed) in one direction at a time. The idea was to approximate a square wave input. The Y axis output was as expected, seen in the blue trace in the attached figure. However the X axis output had a peculiar characteristic where the flow reading initially goes in the wrong direction. There is the same effect in reverse when the motion is stopped. This phenomena on the X-axis is having a significant adverse impact on output noise and makes it difficult to use the flow data in a closed loop control system.

The attached figure shows the graphed output from this test (flow quality was above 250 at all times).

I have run the same test with the stable release and it has the same defect. The klt_flow branch does have this defect so it looks like it is a bug in the image processing.

px4flow x axis anomally

how can i just buffer one frame image?

this project buffers two images,which takes off more RAM.
Now i need more RAM to do other work ,so I want to just buffer one frame image.But i am not familiar with the embedded-device programming,anyone could give me some advice?
thank you~

Parameter saving functionality

If I recall correctly,
there isn't a driver written yet to use the on board eeprom (microchip 24FC128??) to be able to save parameters. I would be interested to try my hand at writing it now that I'm back from competition.

Any tips would be appreciated.

README.md outdated, upload-usb no long works

To build, make archives should be ran before make.

Also, make upload-usb results in make: *** No rule to make target 'upload-usb'. Stop. Thus, I have not found a way to flash the unit using the command line. I have tried to run make px4flow-v2_default upload but that results in

make[2]: ~/PX4/Flow/makefiles//baremetal/upload.mk: No such file or directory
make[2]: *** No rule to make target `~/PX4/Flow/makefiles//baremetal/upload.mk'.  Stop.
make[1]: *** [upload] Error 2

Motivation: I am currently trying to flash the PX4Flow unit without the use of qGroundControl. In particular, I'm trying to flash this .px4 file on it. It looks like the current release of qGroundControl (v2.7.1) does not allow flashing with custom firmware on the PX4Flow. so I'm trying to do it via the command line.

Sonar Performance Degradation

Master 91e6
master-91e6

Ae201 (before mode filter etc.)
revert-ae201

I believe that the complexities introduced by the on-board filtering are unwarranted for the performance gain. It also is causing a loss of information as the 0 return code is mapping both out of range close and out of range far to the same value. As a possible solution, I created a branch that adds an error status to the i2c frame (nominal, unint, low, high): jgoppert@9863563 This would also require the same change on the FMU side and some modification to position_estimator_inav.

Increase the maximum exposure

The maximum exposure is now set at 5% of the default. This is really detrimental indoors and for low light settings outdoors. I have manually set it to 50% of the default and it is much more robust.

@LorenzMeier

How to debug the firmware of px4flow in Windows 7 ?

Hi there.
Sorry to bother you. I am a newbie to px4flow and I have spent at least one week to find out the answer of how to debug the firmware of px4flow in Windows 7.
I am using eclipse and a stlink-v2 debugger, hope for a detailed guidebook to debug the px4flow.
Thank you in advance.

Adding new mavlink message

I'm trying to add a new mavlink message for research purposes. Where have you generated the mavlink includes from?

It's rather hard to include the new message type into the generated mavlink files.

px4flow board debug for "USB device not recognized" issues

Hello ,LorenzMeier !
I used STLINK-V2(JTAG) full chip erase px4flow board and build px4 Flow-master file (2015-01-24 Flow-master)
, make all Flow(firmware) for px4flow_bl.elf and px4flow.bin , compiler code Successful and connect STLINK-V2 JTAG ,then STLINK-V2 program px4flow_bl.elf or px4flow.bin to px4flow board in Flow(c/px4/Flow/).restart the board show "USB device not recognized" . the pxflow board
didn't communicated with PC USB, The three LED is lit.
is the problem Bootloader of code jump to app?Ho to process the problem? (I was under the windows compiler and debug PX4 Toolchain v14/eclipse/clonse .)

Thank you very much for your help!
2015-04-02

I2C Integral Frame does not respond properly

I am trying to read the second I2C frame (integral frame) each 50ms. So far I only managed to get the frame ONCE. After that, data is not updated any more. The first frame however works properly.

PX4flow power options

I've been playing with a PX4flow camera using the USB connection and everithing seems to work perfect.

Now I'd like to remove the USB cable and use the USART2 to get the output data. My question is, how can I power the device? Are the schematics publicly available somewhere?

Thank you in advance!

px4 flow downloading problem

Firmware file missing parameter_xml_size key
I meet such question when downloading the px4 flow firmware.Has there anyone else met such situation before?

Error in camera sensor initialisation

Hello,
I would like to report a minor error in MT9V034 camera sensor initialization for PX4Flow module which I have found.
The error is in the file mt9v034.c[0] where there is on line 183 (197 for Context B respectively)

mt9v034_WriteReg16(MTV_V2_CTRL_REG_A, total_shutter_width);

where MTV_V2_CTRL_REG_A is 0x32 and total_shutter_width is defined as 0x1e0 (480 Dec).

I suppose that this is incorrect because according to the datasheet[1] V2_CTRL_REG_A is a voltage control register with allowed values from 0 to 63 and default value of 0x1e used for HDR knee thresholds. I suppose that there should be

183   mt9v034_WriteReg16(MTV_COARSE_SW_TOTAL_REG_A, total_shutter_width);
197   mt9v034_WriteReg16(MTV_COARSE_SW_TOTAL_REG_B, total_shutter_width);

respectively.
Addressing issue of DrTon #41 on a garbage image this is caused by the "feature" of the sensor. It simply stops working when there is massive change in lighting conditions. I suppose that it is somehow related with the AEC and AGC features of the sensor. It is also greatly influenced by how well the lens is focused. I am currently performing experiments with an FPGA based module with mt9v034 sensor so I will post the solution if I will resolve the problem.

Have a nice day,
Petr

[0] https://github.com/PX4/Flow/blob/master/src/mt9v034.c
[1] http://www.aptina.com/assets/downloadDocument.do?id=406

Gyro data question

Dear experts,
I have a question regarding the gyro data manipulation in the main.c line 407:

    /* gyroscope coordinate transformation */
    float x_rate = y_rate_sensor; // change x and y rates
    float y_rate = - x_rate_sensor;
    float z_rate = z_rate_sensor; // z is correct

I do not understand why x and y data is assign in reverse. I thought that even if the gyro is in up down direction when using the board but y direction also points to the front, so why does y data is assigned to x_rate? please clarify me. Thanks!

Understanding the flow code (flow.c)

Hi!

I have actually bought a PX4FLOW. It is the first time I work with image processing and I am really interested of knowing about how it works. I have been trying to understand the code but I have some questions.
My problem is not the sintaxis of the code (I can find it on the internet), what I don't understand is the use/ utility of some functions. I think that with a short definition of some functions should be enough to start understanding everything.

I know that it is based on SAD algorithm which takes the sum of the absolute diferences on each pixel. I have seen that the lower is the sum, the more similar are the 2 images. The functions I don't understand are the next ones:

1.-
https://github.com/PX4/Flow/blob/4a314cfdb099aed9795b825e7518203771207fbb/src/modules/flow/flow.c#L62
I think it is doing the SAD algorithm taking the difference on the images?

2.-
https://github.com/PX4/Flow/blob/4a314cfdb099aed9795b825e7518203771207fbb/src/modules/flow/flow.c#L62
Why it is a 4x4 pattern taken?
I have been reading about why is interesting to take the average pixel gradient but I continue without understanding why is so interesting and why it is used for knowing if the pixel is suitable for flow tracking:
https://github.com/PX4/Flow/blob/4a314cfdb099aed9795b825e7518203771207fbb/src/modules/flow/flow.c#L433

3.-https://github.com/PX4/Flow/blob/4a314cfdb099aed9795b825e7518203771207fbb/src/modules/flow/flow.c#L221

I think I understand this function : It does the SAD algorithm for a 8x8 pattern taken from the two photos of (188*120). It only takes a 8x8 pattern to make the process quicklier and computable, isn't it?. For analyzing the pixels, it analyze each bit of each pixel and takes de diference with the other image, so the ABSDIFF of EACH BIT of EACH PIXEL should be 1 or 0? It takes a lot of different 8x8 patterns of each photo?

4.- https://github.com/PX4/Flow/blob/4a314cfdb099aed9795b825e7518203771207fbb/src/modules/flow/flow.c#L351

I can see the difference from the above function. Isn't the SAD computation done in the previous step function? Why it is doing again the SAD compute?

That's all, I think if I understand what this functions are used for (Not how are done, why are used) I will be able to understand everything. I have surfing on the internet and I think I understand SAD algorithm, but I don know how it is implemented.

Thank you for your help :)

Expose gyro data via all interfaces and validate

We should expose all gyro data and cross-check that rates and readout speed make sense. We should also include a flag to indicate wether the gyro data is available (in case we want to remove the sensor later if we conclude its not useful).

Getting velocities from message

I'm trying to get the angular velocities and translational velocities from the mavlink OPTICAL_FLOW_RAD message.

I'm computing :

linear.x = (flow_rad.integrated_x/flow_rad.integration_time_us)/flow_rad.distance ; // meters per sec
angular.x = flow_rad.integrated_xgyro/flow_rad.integration_time_us; // radians per sec

Does this seem right? Is this the correct approach?

The problem now is that if no flow data is available, integration_time_us becomes zero and I get nan on the velocities. How should I handle this?
Also, I would like the gyro rate data even when flow is unavailable.

And what is the proper way to get the linear velocity on Z ?
@dominiho @LorenzMeier

feature suggestion:

Could it be used to home in on a flashing light/diode ?
Think about the great landing precision we could achieve - once at home/landing location, home in on a flashing LED on the ground, for very precise landing.

potential bug in usb/usart3 forwarding to usart2.

In communication.c

    /* forwarded received messages from usb and usart3 to usart2 */
    uint8_t buf[MAVLINK_MAX_PACKET_LEN];
    uint32_t len;

    /* copy to usart2 */
    len = mavlink_msg_to_send_buffer(buf, msg);
    for (int i = 0; i < len; i++)
    {
        usart2_tx_ringbuffer_push(buf, len);
    }

usart2_tx_ringbuffer_push takes a length, unclear why it's being called len times with the same argument...

Very slow I2C update rate

The flow measurements I am getting via I2C are only available at around 15 Hz, whereas I believe they should be available at about 400 Hz. Is there something I am supposed to change after I download the firmware?

Thanks!

Thomas

px4Flow i2c frame to FMU confused me

 first :px4Flow calculates optical flow  at 400Hz ,but FMU px4Flow driver  default conversion at 10Hz,
  is it suit able for postion estimator ?so I tried average data ,and set FMU converdion quickly,but it works not well .or because optical flow datas are not accuracy. 
secend:px4Flow up accumulated_flow_x and  accumulated_flow_y to I2c frame ,It is accumulated rad/s,not angular speed .it is some mistake here?

SF10 Lidar replacing HRLV Sonar in Px4flow

Recently I replaced the HRLV MaxBotics Sonar of PX4Flow with SF10 Lidar . SF10 Lidar's range is 0 to 50 meters as compared to HRLV's 0 to 5 meter.

I managed to integrate the SF10 Lidar successfully but the values won't go beyond 9.9 meter although I made all the necessary changes in the Sonar.c code

Is there any hardware or library limitation in PX4Flow that the range of any range finder integrated to it won't go beyond 9.9 meters.

angular velocity compensation using Z gyro

According to the ICRA 2013 paper, angular compensation should also use the yaw rate to account for the flow induced due to yaw. But looking at flow.c, I see that z_rate (rate of z axis (or yaw) gyro) is not being used for gyro compensation. There is probably a good reason for doing so. Appreciate if someone can give me point me in the right direction to understand why it was done so.

get Postion

Hi , How can i get position (dx,dy,dt) from the PX4Flow
i'm using arduino and the px4flow is connected through I2C
Note i can get all the i2c output like velocities, altitude and gyro but i need to know how to use the i2c output to compute the position

OPTICAL_FLOW_RAD polluting i2c when used on PixHawk running ArduCopter

Hi guys,

We've been trying to use the px4flow on our pixhawk running arducopter, but our major problem was that the i2c bus was so polluted that we suffered from lots of data losses and delays: sometimes the signal got blocked for seconds and even tens of seconds !

We found out that there was that OPTICAL_FLOW_RAD mavlink message, which seemed to us like a perfect clone of the OPTICAL_FLOW message, being sent at the same time as the OPTICAL_FLOW messages, and only one of the two were consummed on the ardupilot (arducopter) end.

The fix that we found and spectacularly resolved all of our problems was just commenting the lines where that "clone" message was sent over i2c.

I don't know what is the primary use of that message, if it is a suitable way to fix the problem or if that problem should be addressed on the ardupilot's end or on the px4flow's end, so that's why I'm signaling and asking you.

Cheers.

Implement reboot command

Unfortunately developers are too hasty to read the docs - because the reboot command is not implemented, the auto-firmware upgrade "doesn't work" (unless you follow the instructions and plug the board AFTER having hit the scan button).

We should fix this, and its super-trivial. On this line:
https://github.com/PX4/Flow/blob/08c205bde6994c3b1424ca04c5cc0996d82fca72/src/communication.c#L314

Implement this:
https://github.com/PX4/Firmware/blob/master/src/modules/commander/commander.cpp#L2083

The code below should be complete and compile and reboot the board to boot loader if requested.

#define ARMV7M_NVIC_BASE                0xe000e000
#define NVIC_AIRCR_OFFSET               0x0d0c /* Application interrupt/reset contol registr */
#define NVIC_AIRCR                      (ARMV7M_NVIC_BASE + NVIC_AIRCR_OFFSET)
#define NVIC_AIRCR_PRIGROUP_MASK        (7 << NVIC_AIRCR_PRIGROUP_SHIFT)
#define NVIC_AIRCR_VECTKEY_SHIFT        (16)      /* Bits 16-31: VECTKEY */
#define NVIC_AIRCR_SYSRESETREQ          (1 << 2)  /* Bit 2:  System reset */

#define STM32_PWR_BASE       0x40007000     /* 0x40007000-0x400073ff: Power control PWR */
#define STM32_PWR_CR_OFFSET    0x0000  /* Power control register */
#define PWR_CR_DBP             (1 << 8)  /* Bit 8: Disable Backup Domain write protection */

# define getreg32(a)          (*(volatile uint32_t *)(a))
# define putreg32(v,a)        (*(volatile uint32_t *)(a) = (v))

void stm32_pwr_enablebkp(void)
{
  modifyreg32(STM32_PWR_BASE + (uint32_t)STM32_PWR_CR_OFFSET, (uint32_t)0, (uint32_t)PWR_CR_DBP);
}

void up_systemreset(void) noreturn_function;

void up_systemreset(void)
{
  uint32_t regval;

  /* Set up for the system reset, retaining the priority group from the
   * the AIRCR register.
   */

  regval  = getreg32(NVIC_AIRCR) & NVIC_AIRCR_PRIGROUP_MASK;
  regval |= ((0x5fa << NVIC_AIRCR_VECTKEY_SHIFT) | NVIC_AIRCR_SYSRESETREQ);
  putreg32(regval, NVIC_AIRCR);

  /* Ensure completion of memory accesses */              

  __asm volatile ("dsb");

  /* Wait for the reset */

  for (;;);
}

void
systemreset(bool to_bootloader)
{
    if (to_bootloader) {
        stm32_pwr_enablebkp();

        /* XXX wow, this is evil - write a magic number into backup register zero */
        *(uint32_t *)0x40002850 = 0xb007b007;
    }
    up_systemreset();

    /* lock up here */
    while(true);
}

master clock of camera, why not using TIM8?

Hi, the page https://pixhawk.org/modules/px4flow
said that the camera is working at 400 Hz. But the fluorescent lamp and LED lamp in my country are flickering at 60 Hz. So, I'd like to fetch the image at 360 Hz or 420 Hz.
And the pin 65 that is connected to camera the MT9V034 is driven by channel 3 of TIM1, but it is named TIM8_CH3_MASTERCLOCK in schematic v1.3.

I thought it might be some reason for using TIM3 instead of TIM8?
Thanks.

Position value from PX4Flow is random

I've been trying to read the X and Y values from PX4Flow for quite a while now (and trying to use offboard indoor control with it).

I've been able to get flow_x and flow_y using mavlink message, but even if I place the PX4Flow in a stationary position, these two values seem completely random and jumps around a lot. Is this suppose to be correct? Maybe the Kalman Filter or some other functions in PX4 firmware is able to decode these seemingly random values somehow? If so, could someone tell me how to get the drone's XY position based on the signal from PX4Flow?

Thanks.

Garbage image in low...middle light conditions

Image from PX4FLOW looks ok when I point it to outside from my window but completely garbarge when I point somewhere in room (not too dark). On attached image something in the middle: brightest part of image are ok, but the rest is garbage. Observation of flow_x/flow_y/quality shows that it's NOT transmission problem, but problem of reading from sensor.
Hardware: PX4FLOW v1.3
Firmware: latest master for today (baf60dc)

qgc_flow1

PX4 Optical Flow Kit errors

Hello.

I have a HobbyKings S500 QUADCOPTER and just brought a PX4 Optical Flow Kit and i encounter some problems with it. This is the product :
https://pixhawk.org/modules/px4flow

I am using ArduCopter 3.3 (don't know what RC, maybe the lastest)

I encounter a dozens of problems :

  1. When i am running the DRONE from the battery i see no optical flow in dataflash logs at all.
  2. When i am running the DRONE from the battery sometimes i see BAD GYRO HEALTH error and can't ARM because of this, sometimes not.
  3. When i am running from USB, i can see OF logs in dataflash logs, but the EKF5.meaRng is just a flat line, even though i change the height of the drone, i see nothing. If the sonar was working i should see a more precise ALTITUDE, right?
  4. When i am running from USB, i see "Bad LiDAR Health" and in QgroundController i see "pre arm check range finder" errors

DATAFASH LOG 1 (when i have the usb connected)
http://www.filedropper.com/2016-03-3007-10-304onusb

DATAFLASH LOG 2 (when i give current from the battery)
http://www.filedropper.com/2016-03-3007-10-053onbattery

I also had to change FLOW_ORIENT_YAW from 0 to -9000 in order to calibrate the sensor.

I have updated the firmware of PX4FLOW using the px4flow-klt-06Dec2014.px4 file (found here http://ardupilot.com/downloads/?did=118) where some says that is the best.

How it looks like now when running from USB :
[IMG1] IMU.GyrX with FlowX and BodyX
http://tinypic.com/view.php?pic=ak7sba&s=9#.Vvvli3o9DUc

[IMG2] IMU.GyrY with FlowY and BodyY
http://tinypic.com/view.php?pic=ak7sba&s=9#.Vvvl33o9DUc

[IMG3] EFK5.meaRng
http://tinypic.com/view.php?pic=2qjyd76&s=9#.VvvmUHo9DUc

Other images :
http://imgur.com/a/pMTqL

The dataflash logs are just tests, i was not flying drone, just moving it around from hand.

TUTORIALS :
http://ardupilot.org/copter/docs/common-px4flow-overview.html
http://diydrones.com/forum/topics/optical-flow-discussion-thread?commentId=705844%3AComment%3A2137861&xg_source=activity (Goro Senzai post)

Any ideea? Please.

Thanks.

Baud rate on UART port 3

I checked with an oscilloscope and it seems that the baud rate on the UART port 3 is around 120k which is not close to the desired value of 115.2k. This is causing some issues when trying to read the data from the sensor via the UART port.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.