A Way To Compute the Time Derivative of a Translation Jacobian

classic Classic list List threaded Threaded
3 messages Options
Reply | Threaded
Open this post in threaded view
|

A Way To Compute the Time Derivative of a Translation Jacobian

robotsrule
Hi,

In a motion planning project, we are planning a trajectory with joint accelerations. We want to map the joint accelerations to the acceleration of a point on a robot arm in workspace. It turns out that the time derivative of the translation Jacobian (dJ / dt) is needed, where the J is the Jacobian corresponding to the point on the robot arm. We are wondering what's the simplest way to compute it in OpenRAVE. And do we have access to FK in an analytical form?

Thank you very much for your attention. And we are looking forward to your reply.

Best,
Xinyan
Reply | Threaded
Open this post in threaded view
|

Re: A Way To Compute the Time Derivative of a Translation Jacobian

Rosen Diankov
Administrator
Dear Xinyan,

the derivative of a jacobian is called a hessian. luckily, openrave has those functions:

KinBody::ComputeHessianTranslation
KinBody::ComputeHessianAxisAngle

a great paper on how to use them is:

Arjang Hourtash. "The Kinematic Hessian and Higher Derivatives", IEEE Symposium on Computational Intelligence in Robotics and Automation (CIRA), 2005.

hope this helps,


2015-04-04 11:36 GMT+09:00 robotsrule <[hidden email]>:
Hi,

In a motion planning project, we are planning a trajectory with joint
accelerations. We want to map the joint accelerations to the acceleration of
a point on a robot arm in workspace. It turns out that the time derivative
of the translation Jacobian (dJ / dt) is needed, where the J is the Jacobian
corresponding to the point on the robot arm. We are wondering what's the
simplest way to compute it in OpenRAVE. And do we have access to FK in an
analytical form?

Thank you very much for your attention. And we are looking forward to your
reply.

Best,
Xinyan



--
View this message in context: http://openrave-users-list.185357.n3.nabble.com/A-Way-To-Compute-the-Time-Derivative-of-a-Translation-Jacobian-tp4027297.html
Sent from the OpenRAVE Users List mailing list archive at Nabble.com.

------------------------------------------------------------------------------
Dive into the World of Parallel Programming The Go Parallel Website, sponsored
by Intel and developed in partnership with Slashdot Media, is your hub for all
things parallel software development, from weekly thought leadership blogs to
news, videos, case studies, tutorials and more. Take a look and join the
conversation now. http://goparallel.sourceforge.net/
_______________________________________________
Openrave-users mailing list
[hidden email]
https://lists.sourceforge.net/lists/listinfo/openrave-users


------------------------------------------------------------------------------
Dive into the World of Parallel Programming The Go Parallel Website, sponsored
by Intel and developed in partnership with Slashdot Media, is your hub for all
things parallel software development, from weekly thought leadership blogs to
news, videos, case studies, tutorials and more. Take a look and join the
conversation now. http://goparallel.sourceforge.net/
_______________________________________________
Openrave-users mailing list
[hidden email]
https://lists.sourceforge.net/lists/listinfo/openrave-users
Reply | Threaded
Open this post in threaded view
|

Re: A Way To Compute the Time Derivative of a Translation Jacobian

Xinyan Yan
Dear Rosen,

That's exactly what we what. Thank you so much!

Xinyan

On Sat, Apr 4, 2015 at 3:25 AM, Rosen Diankov <[hidden email]> wrote:
Dear Xinyan,

the derivative of a jacobian is called a hessian. luckily, openrave has those functions:

KinBody::ComputeHessianTranslation
KinBody::ComputeHessianAxisAngle

a great paper on how to use them is:

Arjang Hourtash. "The Kinematic Hessian and Higher Derivatives", IEEE Symposium on Computational Intelligence in Robotics and Automation (CIRA), 2005.

hope this helps,


2015-04-04 11:36 GMT+09:00 robotsrule <[hidden email]>:
Hi,

In a motion planning project, we are planning a trajectory with joint
accelerations. We want to map the joint accelerations to the acceleration of
a point on a robot arm in workspace. It turns out that the time derivative
of the translation Jacobian (dJ / dt) is needed, where the J is the Jacobian
corresponding to the point on the robot arm. We are wondering what's the
simplest way to compute it in OpenRAVE. And do we have access to FK in an
analytical form?

Thank you very much for your attention. And we are looking forward to your
reply.

Best,
Xinyan



--
View this message in context: http://openrave-users-list.185357.n3.nabble.com/A-Way-To-Compute-the-Time-Derivative-of-a-Translation-Jacobian-tp4027297.html
Sent from the OpenRAVE Users List mailing list archive at Nabble.com.

------------------------------------------------------------------------------
Dive into the World of Parallel Programming The Go Parallel Website, sponsored
by Intel and developed in partnership with Slashdot Media, is your hub for all
things parallel software development, from weekly thought leadership blogs to
news, videos, case studies, tutorials and more. Take a look and join the
conversation now. http://goparallel.sourceforge.net/
_______________________________________________
Openrave-users mailing list
[hidden email]
https://lists.sourceforge.net/lists/listinfo/openrave-users




--
要让世界听见我们的歌

------------------------------------------------------------------------------
One dashboard for servers and applications across Physical-Virtual-Cloud
Widest out-of-the-box monitoring support with 50+ applications
Performance metrics, stats and reports that give you Actionable Insights
Deep dive visibility with transaction tracing using APM Insight.
http://ad.doubleclick.net/ddm/clk/290420510;117567292;y
_______________________________________________
Openrave-users mailing list
[hidden email]
https://lists.sourceforge.net/lists/listinfo/openrave-users