Hi all,
I'm trying to operate the Arducopter via MAVlink from my ROS node indoors, and one of the stumbling blocks is the lack of fused IMU velocity updates in the GLOBAL_POSITION_INT packet. I only get altitude values in this packet and 0s for velocities, perhaps since the ArduCopter expects to have some initial GPS data?
If I were to implement sending my own LOCAL_POSITION_NED packet in the ArduCopter source, what internal data member should I use? g_gps, which is already used in the global_position packet will clearly not help. Should I then just resort to integrating the raw accelerometer values?
I want to exploit any fused velocity calculations onboard, especially after attaching an optical sensor. Since I can already get fused angular positions and velocities, why can't I get similar velocities without the GPS?
Or am I just doing something wrong?
Thanks!
Replies
Hi, Randy
I am working on indoor navigation, I am using ArduCopter v3.2.1 code.
I want to get current velocity and position from inertial_nav without GPS, and I follow your tips: in v3.2.1, set_current_position() change to setup_home_position(), so I call inertial_nav.setup_home_position() in userhook_init().
I can get correct fused angular (pitch, yaw,roll) from ahrs, but the velocity and position data from inertial_nav.get_velocity_xy()
inertial_nav.get_position()
are wrong, they keep increasing though I have not move the quad-copter.
Am I missing something need to be initialized about GPS?
Thanks!
Hey Jack,
What you're probably seeing is drift caused by the accelerometers. Just as the compass is used to counteract gyro drift, the GPS (or optical flow) must be used to counteract accelerometer drift.
I don't know of any solution that will allow calculating the position without an absolute position or velocity sensor (i.e. GPS or optical flow)
Thanks for your reply, Randy
I will try to attach a optical sensor to achieve the navigation, though my copter may work in a dark enviroment.
Thank you!
Hi Randy,
So I was trying out the Optical flow sensor today (finally!) and I can confirm that I get the same build issues as others have in trying to build the example sketch while attempting to build under linux with an APM 2.5, and Optical Flow 1.0. I fixed it by adding a #define CONFIG_HAL_BOARD HAL_BOARD_APM2 to the beginning of the sketch.
Although it does build, (and I'm hardcoding the A3 pin number, 57, in the constructor of flowsensor(), since the macro you have suggested in the wiki doesn't exist/I don't know how keywords.txt works), when I connect via the serial port, the code seems to be crashing and resetting repeatedly, i.e., I keep getting
ArduPilot Mega OpticalFlow library test ver 1.5
on the serial line repeatedly. A few quick print messages seem to suggest that something bad's happening in the flowsSensor.init() method.
Any suggestions?
Hi, I'm having a somewhat similiar problem. I have a ROS node setup and I think it's working fine. I'm attempting to control the throttle via ROS. I can see that the APM is Armed (by viewing the ROS topic /state) and I believe my code on the APM is executing properly (I can watch it execute by sending gcs_send_text_p messages to my ROS node). Also, I am using the MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST command in the GCS_Mavlink and again I believe this is working correctly. I However, I can't get any pwm signal to show up by using the set_throttle_out(). I tried using set_throttle_out(1.0,false),set_throttle_out(100.0,false), set_throttle_out(1000,false) etc and I can't get any change.
I am able to use the rc_override mavlink command successfully. If anyone has any tips let me know.
KSS,
Sounds like you're up to some pretty complex work. We've been talking in the dev team about fusing the optical flow sensor values into the inertial navigation solution so if you can do it somehow, we'd love to pull it into trunk.
Really I think you want to extend the AP_InertialNav library and create a new correct_with_optflow() method.
By the way, the accelerometer based velocity can be pulled from the library with these calls
inertial_nav.get_latitude_velocity()
inertial_nav.get_longitude_velocity()
but as you say, they currently rely on a gps...or rather they won't start providing values until the inertial_nav's home lat & lon is set. You could set that to some arbitrary value though.
Good luck.