Skip to content
This repository has been archived by the owner on Nov 13, 2017. It is now read-only.

Better documentation and formatting #244

Merged
merged 1 commit into from
May 31, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
27 changes: 17 additions & 10 deletions robot_model/include/moveit/robot_model/joint_model_group.h
Original file line number Diff line number Diff line change
Expand Up @@ -393,8 +393,8 @@ class JointModelGroup
double distance(const double *state1, const double *state2) const;
void interpolate(const double *from, const double *to, double t, double *state) const;

/** \brief Get the number of variables that describe this joint group. This includes variables necessary for mimic joints, so will always be >=
the number of items returned by getActiveVariableNames() */
/** \brief Get the number of variables that describe this joint group. This includes variables necessary for mimic
joints, so will always be >= the number of items returned by getActiveVariableNames() */
unsigned int getVariableCount() const
{
return variable_count_;
Expand Down Expand Up @@ -450,7 +450,8 @@ class JointModelGroup
/** \brief Set the name of the end-effector, and remember this group is indeed an end-effector. */
void setEndEffectorName(const std::string &name);

/** \brief If this group is an end-effector, specify the parent group (e.g., the arm holding the eef) and the link the end effector connects to */
/** \brief If this group is an end-effector, specify the parent group (e.g., the arm holding the eef) and the link the end
effector connects to */
void setEndEffectorParent(const std::string &group, const std::string &link);

/** \brief Notify this group that there is an end-effector attached to it */
Expand Down Expand Up @@ -540,8 +541,8 @@ class JointModelGroup
void setDefaultIKAttempts(unsigned int ik_attempts);

/** \brief Return the mapping between the order of the joints in this group and the order of the joints in the kinematics solver.
An element bijection[i] at index \e i in this array, maps the variable at index bijection[i] in this group to the variable at index
i in the kinematic solver. */
An element bijection[i] at index \e i in this array, maps the variable at index bijection[i] in this group to
the variable at index i in the kinematic solver. */
const std::vector<unsigned int>& getKinematicsSolverJointBijection() const
{
return group_kinematics_.first.bijection_;
Expand All @@ -554,7 +555,9 @@ class JointModelGroup

bool computeIKIndexBijection(const std::vector<std::string> &ik_jnames, std::vector<unsigned int> &joint_bijection) const;

/** \brief Update the variable values for the state of a group with respect to the mimic joints. This only updates mimic joints that have the parent in this group. If there is a joint mimicking one that is outside the group, there are no values to be read (\e values is only the group state) */
/** \brief Update the variable values for the state of a group with respect to the mimic joints. This only updates
mimic joints that have the parent in this group. If there is a joint mimicking one that is outside the group,
there are no values to be read (\e values is only the group state) */
void updateMimicJoints(double *values) const;

/** \brief Owner model */
Expand Down Expand Up @@ -584,10 +587,12 @@ class JointModelGroup
/** \brief The set of continuous joints this group contains */
std::vector<const JointModel*> continuous_joint_model_vector_;

/** \brief The names of the DOF that make up this group (this is just a sequence of joint variable names; not necessarily joint names!) */
/** \brief The names of the DOF that make up this group (this is just a sequence of joint variable names; not
necessarily joint names!) */
std::vector<std::string> variable_names_;

/** \brief The names of the DOF that make up this group (this is just a sequence of joint variable names; not necessarily joint names!) */
/** \brief The names of the DOF that make up this group (this is just a sequence of joint variable names; not
necessarily joint names!) */
std::set<std::string> variable_names_set_;

/** \brief A map from joint names to their instances. This includes all joints in the group. */
Expand All @@ -610,7 +615,8 @@ class JointModelGroup
/** \brief The list of index values this group includes, with respect to a full robot state; this includes mimic joints. */
std::vector<int> variable_index_list_;

/** \brief For each active joint model in this group, hold the index at which the corresponding joint state starts in the group state */
/** \brief For each active joint model in this group, hold the index at which the corresponding joint state starts in
the group state */
std::vector<int> active_joint_model_start_index_;

/** \brief The links that are on the direct lineage between joints
Expand Down Expand Up @@ -669,7 +675,8 @@ class JointModelGroup
/** \brief If an end-effector is attached to this group, the name of that end-effector is stored in this variable */
std::vector<std::string> attached_end_effector_names_;

/** \brief First: name of the group that is parent to this end-effector group; Second: the link this in the parent group that this group attaches to */
/** \brief First: name of the group that is parent to this end-effector group; Second: the link this in the parent group
that this group attaches to */
std::pair<std::string, std::string> end_effector_parent_;

/** \brief The name of the end effector, if this group is an end-effector */
Expand Down
6 changes: 3 additions & 3 deletions robot_state/include/moveit/robot_state/robot_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -770,7 +770,7 @@ as the new values that correspond to the group */
/** \brief Compute the sequence of joint values that correspond to a straight Cartesian path for a particular group.

The Cartesian path to be followed is specified as a direction of motion (\e direction, unit vector) for the origin of a robot
link (\e link_name). The direction is assumed to be either in a global reference frame or in the local reference frame of the
link (\e link). The direction is assumed to be either in a global reference frame or in the local reference frame of the
link. In the latter case (\e global_reference_frame is false) the \e direction is rotated accordingly. The link needs to move in a
straight line, following the specified direction, for the desired \e distance. The resulting joint values are stored in
the vector \e traj, one by one. The maximum distance in Cartesian space between consecutive points on the resulting path
Expand All @@ -794,7 +794,7 @@ as the new values that correspond to the group */
/** \brief Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular group.

The Cartesian path to be followed is specified as a target frame to be reached (\e target) for the origin of a robot
link (\e link_name). The target frame is assumed to be either in a global reference frame or in the local reference frame of the
link (\e link). The target frame is assumed to be either in a global reference frame or in the local reference frame of the
link. In the latter case (\e global_reference_frame is false) the \e target is rotated accordingly. The link needs to move in a
straight line towards the target. The resulting joint values are stored in
the vector \e traj, one by one. The maximum distance in Cartesian space between consecutive points on the resulting path
Expand All @@ -818,7 +818,7 @@ as the new values that correspond to the group */
/** \brief Compute the sequence of joint values that perform a general Cartesian path.

The Cartesian path to be followed is specified as a set of \e waypoints to be sequentially reached for the origin of a robot
link (\e link_name). The waypoints are transforms given either in a global reference frame or in the local reference frame of the
link (\e link). The waypoints are transforms given either in a global reference frame or in the local reference frame of the
link at the immediately preceeding waypoint. The link needs to move in a straight line between two consecutive waypoints.
The resulting joint values are stored in the vector \e traj, one by one. The maximum distance in Cartesian space between
consecutive points on the resulting path is specified by \e max_step. If a \e validCallback is specified, this is passed to the
Expand Down
1 change: 1 addition & 0 deletions transforms/include/moveit/transforms/transforms.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ class Transforms : private boost::noncopyable

/**
* @brief Transform a vector in from_frame to the target_frame
* Note: assumes that v_in and v_out are "free" vectors, not points
* @param from_frame The frame from which the transform is computed
* @param v_in The input vector (in from_frame)
* @param v_out The resultant (transformed) vector
Expand Down