Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

TrajectoryTask usage #26

Open
ahundt opened this issue Apr 20, 2017 · 7 comments
Open

TrajectoryTask usage #26

ahundt opened this issue Apr 20, 2017 · 7 comments

Comments

@ahundt
Copy link

ahundt commented Apr 20, 2017

What HighLevelTasks would you feed to a TrajectoryTask?
Also should separate ones be created for position, velocity, and orientation control?
Is there any chance a small example could be created like for the other tasks/unit tests?

Also, which Tasks in QPTasks.h are deprecated/unused again?

@haudren
Copy link
Collaborator

haudren commented Apr 21, 2017

We typically use a lot of HighLevelTasks: in our framework, we currently have helpers for:

  • PositionTask
  • OrientationTask
  • CoMTask
  • GazeTask
  • PositionBasedVisServoTask
  • VectorOrientationTask

There are few more things that can be used, but those should be a good start.

For Tasks, the only thing that's deprecated is PIDTask.
You can thus use:

  • SetPointTask to servo around a fixed reference
  • TrajectoryTask to follow a task-space trajectory
  • TrackingTask to follow an error-space trajectory (Basically, in TrajectoryTask, the error is automatically computed from the HighLevelTask, but this is not always possible, for example if the error depends on external sensors, e.g. force sensors).
  • TargetObjectiveTask to reach a target in a certain time. WARNING this gets quite unstable when you approach the time limit.

In your example, if you want to follow a 6D trajectory, yes, you should create one per objective. I'll write here a small example (might not compile):

// Load all your data here
// Either something like 
// std::vector<Eigen::Vector3d> positions = loadFromFile()
// or
// Generator positions = trajectory.generate()...
// I'll assume the latter for this example.
tasks::qp::PositionTask posTask(mbs, robotIndex, "EF", Eigen::Vector3d(0, 0, 0));
tasks::qp::OrientationTask oriTask(mbs, robotIndex, "EF", Eigen::Matrix3d::Identity());
tasks::qp::TrajectoryTask posTrajTask(mbs, robotIndex, &posTask, 100, 20, 100);
tasks::qp::TrajectoryTask oriTrajTask(mbs, robotIndex, &oriTask, 100, 20, 100);

solver.addTask(posTrajTask);
solver.addTask(oriTrajTask);

for(std::size_t i = 0; i < positions.size(); ++i)
{
    posTask.position(positions.next());
    posTrajTask.refVel(linearSpeeds.next());
    oriTask.orientation(orientations.next());
    oriTrajTask.refVel(rotationSpeeds.next());
    solver.solve();
}

@stephane-caron
Copy link
Contributor

stephane-caron commented Apr 21, 2017

Suggestion: copy-paste this into the project wiki. (Time cost is almost zero, and docs always help.)

Edit: I actually went forward with a tentative page. Feel free to edit, or remove if you disagree.

@ahundt
Copy link
Author

ahundt commented Apr 21, 2017

@haudren thanks I'll give that a shot it isn't too different from before. @stephane-caron good idea

@haudren
Copy link
Collaborator

haudren commented Apr 24, 2017

Thank you Stéphane and @ahundt don't hesitate if you have more questions. Note that I did not cover it here, but you can also supply a reference acceleration.

@haudren
Copy link
Collaborator

haudren commented May 19, 2017

@ahundt : Did you manage to do what you wanted? If yes, I will close this issue :)

@ahundt
Copy link
Author

ahundt commented May 19, 2017

I had hit the end of my last semester so I got sidetracked. I'll be coming back to it soon.

@ahundt
Copy link
Author

ahundt commented Jun 22, 2018

I need to:

  1. Follow a fixed path defined in a moving frame.
    • In other words imagine I was trying to cut a shape out of a wood block as accurately as I can, but that block may shift as cutting proceeds. I have a camera to detect the shift and update the new block position, but I need to modify the trajectories accordingly.
  2. Move in an absolutely straight line without orientation changes in cartesian space

Would any of the existing tasks be suitable for that? Can PositionBasedVisServoTask be used to control both position and orientation changes at each time step?

Might have been a bit longer delay than I imagined before coming back to this! Had to get some low level stuff working, and now I'm seeing trouble where tasks isn't taking a straight line to goals I set in real time. Tuning the weights helped but isn't sufficient. Right now I'm primarily using a position task and an orientation task, but I'm not sure if there is a way to lock it on to a Cartesian straight line path to the goals with a locked orientation as well.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants