dennisss / tansa

Dancing Robotics Platform
MIT License
39 stars 16 forks source link

spiral trajectory #160

Open schweinebauch opened 6 years ago

schweinebauch commented 6 years ago

Hello @dennisss I tested your spiral trajectory, this trajectory can update position in XY(z = 0) plane, but I want to update this trajectory in XYZ, how can I modify spiral.py so that it can generate new s.position s.velocity and s.acceleration? Could you please help me ? @dennisss

dennisss commented 6 years ago

@schweinebauch that largely depends on what you want to do with it.

The purpose of that script is to simply take the symbolic expressions for the position and generate the equations for you. Changing the position equations should only require changing this line (https://github.com/dennisss/tansa/blob/master/src/trajectory/spiral.py#L24) and/or the lines above it.

But in general, the primitives exposed for trajectories are intentionally basic and the general pattern we use is to build up compound and matrix transformed trajectories (https://github.com/dennisss/tansa/blob/master/include/tansa/trajectory.h#L159) from the primitive classes. i.e. you could trivially come up with your own pos-vel-accel equations for just the Z axis and literally add them to a spiral trajectory.

schweinebauch commented 6 years ago

Hello @dennisss, make sense! Thanks for your help I modified what you said. Another question is, as you mentioned, this script is to simply take the symbolic expressions, there is no control feedback in it, trajectory errors can not be corrected.How can you guarantee the trajectory precision? Looking forward to receiving your help. @dennisss

dennisss commented 6 years ago

@schweinebauch there's separate controller logic for following the trajectory (https://github.com/dennisss/tansa/blob/master/src/control/position.cpp#L500). It's the traditional PID controller approach that is discussed in most papers on this topic. It takes the current position in time of the trajectory of uses that as the PID setpoint and compares it to some externally given measurement of the current position. The output of that is an attitude/acceleration command to send to the drone.

Whether or not the controller will actually converge to the trajectory is a completely different issue of feasibility of the trajectory. Given pre-estimated maximum acceleration and velocity capabilities of a drone, we verify that a trajectory is physically possibly (https://github.com/dennisss/tansa/blob/master/src/model/feasibility.cpp) before ever running it through a live controller.

schweinebauch commented 6 years ago

@dennisss Many thanks! You mentioned "the output of that is an attitude/acceleration command to send to the drone", under my understanding the PID calculated commands are sent to the inner control loop? @dennisss

dennisss commented 6 years ago

@schweinebauch yes. In our case, we send it over WiFi to become the input to PX4's inner attitude controller loop onboard and that outputs roll/pitch/yaw rates which are finally translated into motor commands based on the drone's geometry.

schweinebauch commented 6 years ago

@dennisss thanks, make sense.Under my understanding, I think the evaluate() function calculates the setpoint of trajectory and measured position (maybe from ekf in inner controller loop) is as current position. The PID controller controls the errors between them which mentioned above. The outputs of PID also position, velocity and acceleration command will be sent to inner loop. This is my opinion. Is it right?Because I think PID controller is much more easier to design and implement. Looking forward to your detailed suggestion.

dennisss commented 6 years ago

@schweinebauch sounds mostly correct. the measured pos/vel can be whatever you want as long as it is very accurate. we use a filtered motion capture position reading that we over time differentiate into a velocity reading as well (we don't use any data from the inner loop in the outer loop). the inner ekf in our case is only responsible for maintaining an attitude measurement.

the input of our outer loop is the the measured pos/vel and the target pos/vel. As you mentioned correctly, the error is weighted to create the output. But the output in our implementation is ONLY the acceleration Note: we don't output a position or velocity command in this stage

Note that the target accel is not a part of the PID controller but is purely a feed forward term. we run the PID on pos/vel error to create an error correction command in terms of acceleration units and we then add the trajectory's acceleration to that before sending the command (without the feed forward addition, the PID output would only converge to a state with constant position and velocity)

the inner loop only receives a single scalar acceleration value per axis

schweinebauch commented 6 years ago

@dennisss make sense. You are very kind!!! Thanks for your detailed answers. Is there a method in your work to control velocity? I mean in "compound trajectory" two trajectories are added together, can I control the velocity respectively?For example I will add three trajectories together, the first one is a line, second one is semi-circle and third one is a line as well. Can I control the UAV velocity like this : 4m/s (in first trajectory)--> 1m/s(in second trajectory) --> 4m/s(in third trajectory)? One more question is, can I control UAV velocity constantly while flying? How can I modify your code?

Thanks!!

@dennisss

dennisss commented 6 years ago

@schweinebauch the LinearTrajectory primitives in here are approximately constant velocity (defined in terms of time and distance). Actually the transition curve for them is approximately sigmoidal in shape as they assume zero velocity and acceleration at the endpoints so must smoothly ramp up and ramp down velocity/acceleration to avoid discontinuities in the velocity/acceleration states. We use this whenever we need lines and you can't really tell the difference between constant-velocity lines.

If you actually want fixed velocity states, look into the PolynomialTrajectories (https://github.com/dennisss/tansa/blob/e6044af397f99b9b985ed56015e9e0be13d4b026/include/tansa/trajectory.h#L256) which have a helper compute() that will compute any smooth (optimal minimum-jerk transitions) trajectories between a start and end state (where each state is a list of position, velocity, and acceleration vectors).

Regarding the second question, the controllers we implemented do not support changes to list of trajectories being executed, but as long as you enforce state continuity without jumps in velocity, I wouldn't see why that couldn't be implemented. You'd probably need to reimplement a light version of our JocsPlayer class for that (which right now just operates of a fixed list of trajectories given before hand)

But, we generally don't support 'RC' style controls (single vector either pos/vel/accel but not all at once). All the trajectories are defined in terms of start of end times and states with well-defined values for all derivates of position and no discontinuities in any derivatives. If you need direct RC / velocity control, then the trajectories are overkill for you. You'd be better off directly sending PX4 velocity commands. But if your application can be defined in terms of a smooth set of trajectories to follow which is gradually refined over time then our trajectory utilities are suited for that.

schweinebauch commented 6 years ago

@dennisss make sense! many thanks!