Closed GalBrandwine closed 3 years ago
rosrun crazyflie_tools listParams --uri <URI-of-CF>
to find a list of all parameters and you can use listLogVariables
to find a list of all variables you can log. Unfortunately, there is no documentation on what the variables actually mean (and what the units are), apart from reading the crazyflie firmware code.@GalBrandwine did you ever get good results using the Flow deck with crazyswarm?
I tested this with one CF a few days ago. It works. I'll soon share a PR that adds pose visualization for that case (and the case where other loco systems are used). One problem I see is that sometimes the EKF diverges while the quad is still on the ground and in that case one should obviously not take off.
Are there any updates on this? I also experience a diverging EKF when flying only with the flow deck. Usually I can take off and land once or twice before the EFK diverges while the CF is sitting on the ground. Sometimes rebooting helps but often I have to move the drone a bit and reboot again. My settings for the crazyswarm_server
are below and I'm using the default
crazyflie type. I first tried with pNAcc_xy: 1.0
and pNAcc_z: 2
but that seemed even worse.
<node pkg="crazyswarm" type="crazyswarm_server" name="crazyswarm_server" output="screen" >
<rosparam>
world_frame: "/world"
# Logging configuration (Use enable_logging to actually enable logging)
genericLogTopics: ["log1"]
genericLogTopicFrequencies: [10]
genericLogTopic_log1_Variables: ["stateEstimate.x", "stateEstimate.y", "stateEstimate.z"]
# firmware parameters for all drones (use crazyflieTypes.yaml to set per type, or
# allCrazyflies.yaml to set per drone)
firmwareParams:
commander:
enHighLevel: 1
stabilizer:
estimator: 2 # 1: complementary, 2: kalman
controller: 2 # 1: PID, 2: mellinger
ring:
effect: 16 # 6: double spinner, 7: solid color, 16: packetRate
solidBlue: 255 # if set to solid color
solidGreen: 0 # if set to solid color
solidRed: 0 # if set to solid color
headlightEnable: 0
# locSrv:
extPosStdDev: 1e-3
extQuatStdDev: 0.5e-1
kalman:
resetEstimation: 1
# tracking
motion_capture_type: "none" # one of none,vicon,optitrack,qualisys,vrpn
object_tracking_type: "libobjecttracker" # one of motionCapture,libobjecttracker
send_position_only: True # set to False to send position+orientation; set to True to send position only
# vicon_host_name: "vicon"
optitrack_host_name: "192.168.1.249"
# qualisys_host_name: "10.0.5.219"
# qualisys_base_port: 22222
# vrpn_host_name: "vicon"
save_point_clouds: ~/pointCloud.ot
print_latency: False
write_csvs: False
force_no_cache: False
enable_parameters: True
enable_logging: True
</rosparam>
</node>
This is most likely an issue with the EKF in the official firmware. Did you pick their recent improvement (https://github.com/bitcraze/crazyflie-firmware/issues/608)?
I flashed the master branch of the firmware a few days ago, so I think this improvement should be included.
I did a few more tests today made the following observations. We are always flying above textured rubber mats with a black-white pattern. When standing on a white spot, the EFK does not diverte. However, when moving it over a dark/black spot, it diverges almost immediately. When moving from a black to a white spot, it stops diverging and keeps the offset.
When using the tools provided by crazyswarm
, starting and landing on white spots works quite well. When landing on a black spot, the EFK diverges and taking off again is not possible.
When I fly manually with the cfclient
in "assisted flight" hover mode, I do not see any difference between starting from a black spot or a white spot.
I checked the parameters in cfclient
and as far as I can tell, all of them were the same in "manual flight" and "crazyswarm flight". I used PID controller and EFK estimator in both cases.
Does anyone else observed a similar behaviour?
The relevant parameters would be in the kalman
group. Which crazyflie type are you using? If you use defaultSingleMarker
, make sure to comment out https://github.com/USC-ACTLab/crazyswarm/blob/master/ros_ws/src/crazyswarm/launch/crazyflieTypes.yaml#L34-L38. Apart from different settings, the behavior should really not differ between the two modes of operation.
I was using the default
crazyflie type and made sure all parameters were the same. However, after some more testing I also noticed the diverging EFK in manual flight. Therefore, I opened an issue on the firmware repo: https://github.com/bitcraze/crazyflie-firmware/issues/617.
Hello all.
We have sucsesfuly flown 3 crazyflies with optitrack mocap. the hover_swarm.launch, and the figure8_csv.py, worked perfectly.
Now we want to use flow deck: for that we have changed the necesary changed in the hover_swarm.launch file:
(motion_capture_type: "none")
but when we test it by doing:
roslaunch crazyswarm hover_swarm.launch
and than:rosservice call /cfX/takeoff...
But then the crazyflie is going crazy, and not taking off in a stable and elegant way. we use the "log1", to log our stateEstimate.x & stateEstimate.y & stateEstimate.z. they are publishing the initial location of the drone. and when we try to manually lift the drone we receive the correct feedback.
what i want to know: