amino  1.0-beta2
Lightweight Robot Utility Library
scene_sub.h File Reference

Sub-scenegraphs. More...

#include "rxtype.h"
#include "scenegraph.h"

Go to the source code of this file.

Functions

AA_API void aa_rx_sg_sub_destroy (struct aa_rx_sg_sub *sg)
 Destroy the scengraph subset. More...
 
AA_API const struct aa_rx_sgaa_rx_sg_sub_sg (const struct aa_rx_sg_sub *sg_sub)
 Return the original scene graph for the sub-scenegraph.
 
AA_API size_t aa_rx_sg_sub_config_count (const struct aa_rx_sg_sub *sg_sub)
 Return the number of configuration variables in the scenegraph subset.
 
AA_API size_t aa_rx_sg_sub_all_config_count (const struct aa_rx_sg_sub *sg_sub)
 Return the number of configuration variables in the full scenegraph.
 
AA_API size_t aa_rx_sg_sub_frame_count (const struct aa_rx_sg_sub *sg_sub)
 Return the number of frames in the scenegraph subset.
 
AA_API size_t aa_rx_sg_sub_all_frame_count (const struct aa_rx_sg_sub *sg_sub)
 Return the number of frames in the full scenegraph.
 
AA_API aa_rx_config_id aa_rx_sg_sub_config (const struct aa_rx_sg_sub *sg_sub, size_t i)
 Return the full scenegraph config id for the i'th configuration of the sub-scenegraph.
 
AA_API aa_rx_frame_id aa_rx_sg_sub_frame (const struct aa_rx_sg_sub *sg_sub, size_t i)
 Return the full scenegraph frame id for the i'th frame of the sub-scenegraph.
 
AA_API aa_rx_frame_id aa_rx_sg_sub_frame_ee (const struct aa_rx_sg_sub *sg_sub)
 Return the end-effector frame id, if any. More...
 
AA_API size_t aa_rx_sg_sub_frame_ee_count (const struct aa_rx_sg_sub *sg_sub)
 Return the number of end effector frames, if any.
 
AA_API aa_rx_frame_idaa_rx_sg_sub_frame_ees (const struct aa_rx_sg_sub *sg_sub)
 Return an array of end effector frames, if any.
 
AA_API aa_rx_config_idaa_rx_sg_sub_configs (const struct aa_rx_sg_sub *sg_sub)
 Return the array of full scenegraph config ids contained in the sub-scenegraph.
 
AA_API aa_rx_frame_idaa_rx_sg_sub_frames (const struct aa_rx_sg_sub *sg_sub)
 Return the array of full scenegraph frame ids contained in the sub-scenegraph.
 
AA_API void aa_rx_sg_sub_config_get (const struct aa_rx_sg_sub *ssg, size_t n_all, const double *config_all, size_t n_subset, double *config_subset)
 
AA_API void aa_rx_sg_sub_config_set (const struct aa_rx_sg_sub *ssg, size_t n_sub, const double *config_subset, size_t n_all, double *config_all)
 
AA_API void aa_rx_sg_sub_config_scatter (const struct aa_rx_sg_sub *ssg, const struct aa_dvec *config_subset, struct aa_dvec *config_all)
 Fill a full configuration vector with values from the subset vector.
 
AA_API void aa_rx_sg_sub_config_gather (const struct aa_rx_sg_sub *ssg, const struct aa_dvec *config_all, struct aa_dvec *config_subset)
 Fill a subset configuration vector with values from the full vector.
 
AA_API struct aa_rx_sg_sub * aa_rx_sg_chain_create (const struct aa_rx_sg *sg, aa_rx_frame_id root, aa_rx_frame_id tip)
 Create a sub-scenegraph for the kinematic chain starting at root and ending a tip.
 
AA_API void aa_rx_sg_sub_center_configs (const struct aa_rx_sg_sub *ssg, size_t n, double *q)
 Fill q with the centered positions of each configuration.
 
AA_API void aa_rx_sg_sub_center_configv (const struct aa_rx_sg_sub *ssg, struct aa_dvec *q)
 
AA_API void aa_rx_sg_sub_rand_config (const struct aa_rx_sg_sub *ssg, struct aa_dvec *dst)
 
AA_API void aa_rx_sg_sub_jacobian_size (const struct aa_rx_sg_sub *ssg, size_t *rows, size_t *cols)
 Determine the size of the Jacobian matrix for the sub-scenegraph.
 
AA_API void aa_rx_sg_sub_jacobian (const struct aa_rx_sg_sub *ssg, size_t n_tf, const double *TF_abs, size_t ld_TF, double *J, size_t ld_J)
 Compute the Jacobian matrix for the sub-scenegraph.
 
AA_API struct aa_dmataa_rx_sg_sub_get_jacobian (const struct aa_rx_sg_sub *ssg, struct aa_mem_region *reg, const struct aa_dmat *TF_abs)
 Allocate and compute the Jacobian matrix for the sub-scenegraph.
 
AA_API double * aa_rx_sg_sub_alloc_jacobian (const struct aa_rx_sg_sub *ssg, struct aa_mem_region *region)
 Allocate jacobian matrix for sub scene graph.
 
AA_API struct aa_dmataa_rx_sg_sub_jac_twist_get (const struct aa_rx_sg_sub *ssg, struct aa_mem_region *region, const struct aa_rx_fk *fk)
 Allocate and fill the twist Jacobian. More...
 
AA_API void aa_rx_sg_sub_jac_twist_fill2 (const struct aa_rx_sg_sub *ssg, const struct aa_rx_fk *fk, struct aa_dmat *Jp, struct aa_dmat *Jr)
 Fill in the blocks of the twist jacobian. More...
 
AA_API void aa_rx_sg_sub_jac_twist_fill (const struct aa_rx_sg_sub *ssg, const struct aa_rx_fk *fk, struct aa_dmat *J)
 Fill in the blocks of the twist jacobian. More...
 
AA_API struct aa_dmataa_rx_sg_sub_jac_vel_get (const struct aa_rx_sg_sub *ssg, struct aa_mem_region *region, const struct aa_rx_fk *fk)
 Allocate and fill the velocity Jacobian. More...
 
AA_API void aa_rx_sg_sub_jac_vel_fill2 (const struct aa_rx_sg_sub *ssg, const struct aa_rx_fk *fk, struct aa_dmat *Jp, struct aa_dmat *Jr)
 Fill in the blocks of the velocity jacobian. More...
 
AA_API void aa_rx_sg_sub_jac_vel_fill (const struct aa_rx_sg_sub *ssg, const struct aa_rx_fk *fk, struct aa_dmat *J)
 
AA_API double * aa_rx_sg_sub_alloc_config (const struct aa_rx_sg_sub *ssg, struct aa_mem_region *region)
 Allocate sub scene graph config array.
 
AA_API void aa_rx_sg_sub_expand_path (const struct aa_rx_sg_sub *ssg, size_t n_pts, const double *q_start, const double *path_sub, double *path_all)
 Expand sub path to full config path. More...
 
AA_API void aa_rx_fk_sub (struct aa_rx_fk *fk, const struct aa_rx_sg_sub *ssg, const struct aa_dvec *q_sub)
 Compute the forward kinematics for the sub-scenegraph.
 

Detailed Description

Sub-scenegraphs.

Definition in file scene_sub.h.

Function Documentation

◆ aa_rx_sg_sub_destroy()

AA_API void aa_rx_sg_sub_destroy ( struct aa_rx_sg_sub *  sg)

Destroy the scengraph subset.

The original scenegraph will remain valid.

◆ aa_rx_sg_sub_expand_path()

AA_API void aa_rx_sg_sub_expand_path ( const struct aa_rx_sg_sub *  ssg,
size_t  n_pts,
const double *  q_start,
const double *  path_sub,
double *  path_all 
)

Expand sub path to full config path.

Parameters
ssgSub scene graph for the given path
n_ptsNumber of points in the path
q_startA start configuration for joints not in the sub-scenegraph, or NULL to ignore
path_subPath for the sub-scenegraph
path_allThe full scene path

◆ aa_rx_sg_sub_frame_ee()

AA_API aa_rx_frame_id aa_rx_sg_sub_frame_ee ( const struct aa_rx_sg_sub *  sg_sub)

Return the end-effector frame id, if any.

If multiple end-effectors, return the initial.

◆ aa_rx_sg_sub_jac_twist_fill()

AA_API void aa_rx_sg_sub_jac_twist_fill ( const struct aa_rx_sg_sub *  ssg,
const struct aa_rx_fk *  fk,
struct aa_dmat J 
)

Fill in the blocks of the twist jacobian.

\[ \begin{bmatrix} \omega \\ \dot{v} + v \times \omega \end{bmatrix} = J \end{bmatrix} \dot\theta \]

◆ aa_rx_sg_sub_jac_twist_fill2()

AA_API void aa_rx_sg_sub_jac_twist_fill2 ( const struct aa_rx_sg_sub *  ssg,
const struct aa_rx_fk *  fk,
struct aa_dmat Jp,
struct aa_dmat Jr 
)

Fill in the blocks of the twist jacobian.

\[ \begin{bmatrix} \omega \\ \dot{v} + v \times \omega \end{bmatrix} = \begin{bmatrix} J_p \\ J_r \end{bmatrix} \dot\theta \]

◆ aa_rx_sg_sub_jac_twist_get()

AA_API struct aa_dmat* aa_rx_sg_sub_jac_twist_get ( const struct aa_rx_sg_sub *  ssg,
struct aa_mem_region region,
const struct aa_rx_fk *  fk 
)

Allocate and fill the twist Jacobian.

\[ \begin{bmatrix} \omega \\ \dot{v} + v \times \omega \end{bmatrix} = J \dot\theta \]

See also
AA_TF_DX_V
AA_TF_DX_W

◆ aa_rx_sg_sub_jac_vel_fill2()

AA_API void aa_rx_sg_sub_jac_vel_fill2 ( const struct aa_rx_sg_sub *  ssg,
const struct aa_rx_fk *  fk,
struct aa_dmat Jp,
struct aa_dmat Jr 
)

Fill in the blocks of the velocity jacobian.

\[ \begin{bmatrix} \omega \\ \dot{v} \end{bmatrix} = J \dot\theta \]

◆ aa_rx_sg_sub_jac_vel_get()

AA_API struct aa_dmat* aa_rx_sg_sub_jac_vel_get ( const struct aa_rx_sg_sub *  ssg,
struct aa_mem_region region,
const struct aa_rx_fk *  fk 
)

Allocate and fill the velocity Jacobian.

\[ \begin{bmatrix} \omega \\ \dot{v} \end{bmatrix} = J \dot\theta \]

See also
AA_TF_DX_V
AA_TF_DX_W