Skip to content

Commit

Permalink
Finish up API documentation (#123)
Browse files Browse the repository at this point in the history
* Finish up API documentation

Signed-off-by: Stephen Brawner <brawner@gmail.com>

* PR Fixup

Signed-off-by: Stephen Brawner <brawner@gmail.com>
  • Loading branch information
brawner committed Jun 4, 2020
1 parent 49afd68 commit ba32be2
Show file tree
Hide file tree
Showing 12 changed files with 60 additions and 5 deletions.
2 changes: 2 additions & 0 deletions geometry_msgs/msg/InertiaStamped.msg
Original file line number Diff line number Diff line change
@@ -1,2 +1,4 @@
# An Inertia with a time stamp and reference frame.

std_msgs/Header header
Inertia inertia
4 changes: 2 additions & 2 deletions geometry_msgs/msg/Point32.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# This contains the position of a point in free space(with 32 bits of precision).
# It is recommeded to use Point wherever possible instead of Point32.
# It is recommended to use Point wherever possible instead of Point32.
#
# This recommendation is to promote interoperability.
#
Expand All @@ -8,4 +8,4 @@

float32 x
float32 y
float32 z
float32 z
9 changes: 7 additions & 2 deletions geometry_msgs/msg/TransformStamped.msg
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,13 @@
#
# The child_frame_id is necessary in addition to the frame_id
# in the Header to communicate the full reference for the transform
# in a self contained message.
# in a self contained message.

# The frame id in the header is used as the reference frame of this transform.
std_msgs/Header header
string child_frame_id # the frame id of the child frame

# The frame id of the child frame to which this transform points.
string child_frame_id

# Translation and rotation in 3-dimensions of child_frame_id from header.frame_id.
Transform transform
5 changes: 5 additions & 0 deletions nav_msgs/msg/GridCells.msg
Original file line number Diff line number Diff line change
@@ -1,7 +1,12 @@
# An array of cells in a 2D grid

std_msgs/Header header

# Width of each cell
float32 cell_width

# Height of each cell
float32 cell_height

# Each cell is represented by the Point at the center of the cell
geometry_msgs/Point[] cells
7 changes: 7 additions & 0 deletions nav_msgs/msg/Odometry.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,14 @@
# The pose in this message should be specified in the coordinate frame given by header.frame_id
# The twist in this message should be specified in the coordinate frame given by the child_frame_id

# Includes the frame id of the pose parent.
std_msgs/Header header

# Frame id the pose points to. The twist is in this coordinate frame.
string child_frame_id

# Estimated pose that is typically relative to a fixed world frame.
geometry_msgs/PoseWithCovariance pose

# Estimated linear and angular velocity relative to child_frame_id.
geometry_msgs/TwistWithCovariance twist
3 changes: 3 additions & 0 deletions nav_msgs/msg/Path.msg
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
# An array of poses that represents a Path for a robot to follow.

# Indicates the frame_id of the path.
std_msgs/Header header

# Array of poses to follow.
geometry_msgs/PoseStamped[] poses
1 change: 1 addition & 0 deletions nav_msgs/srv/GetMap.srv
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
# Get the map as a nav_msgs/OccupancyGrid
---
# The current map hosted by this map service.
OccupancyGrid map
1 change: 1 addition & 0 deletions nav_msgs/srv/GetPlan.srv
Original file line number Diff line number Diff line change
Expand Up @@ -10,4 +10,5 @@ geometry_msgs/PoseStamped goal
# relax the constraint in x and y before failing.
float32 tolerance
---
# Array of poses from start to goal if one was successfully found.
Path plan
7 changes: 6 additions & 1 deletion nav_msgs/srv/SetMap.srv
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
# Set a new map together with an initial pose

# Requested 2D map to be set.
nav_msgs/OccupancyGrid map

# Estimated initial pose when setting new map.
geometry_msgs/PoseWithCovarianceStamped initial_pose
---
bool success

# True if the map was successfully set, false otherwise.
bool success
8 changes: 8 additions & 0 deletions trajectory_msgs/msg/JointTrajectory.msg
Original file line number Diff line number Diff line change
@@ -1,3 +1,11 @@
# The header is used to specify the coordinate frame and the reference time for
# the trajectory durations
std_msgs/Header header

# The names of the active joints in each trajectory point. These names are
# ordered and must correspond to the values in each trajectory point.
string[] joint_names

# Array of trajectory points, which describe the positions, velocities,
# accelerations and/or efforts of the joints at each time point.
JointTrajectoryPoint[] points
17 changes: 17 additions & 0 deletions trajectory_msgs/msg/JointTrajectoryPoint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,25 @@
# or positions[, effort] for the trajectory to be executed.
# All specified values are in the same order as the joint names in JointTrajectory.msg.

# Single DOF joint positions for each joint relative to their "0" position.
# The units depend on the specific joint type: radians for revolute or
# continuous joints, and meters for prismatic joints.
float64[] positions

# The rate of change in position of each joint. Units are joint type dependent.
# Radians/second for revolute or continuous joints, and meters/second for
# prismatic joints.
float64[] velocities

# Rate of change in velocity of each joint. Units are joint type dependent.
# Radians/second^2 for revolute or continuous joints, and meters/second^2 for
# prismatic joints.
float64[] accelerations

# The torque or the force to be applied at each joint. For revolute/continuous
# joints effort denotes a torque in newton-meters. For prismatic joints, effort
# denotes a force in newtons.
float64[] effort

# Desired time from the trajectory start to arrive at this trajectory point.
builtin_interfaces/Duration time_from_start
1 change: 1 addition & 0 deletions trajectory_msgs/msg/MultiDOFJointTrajectoryPoint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,5 @@ geometry_msgs/Twist[] velocities
# There can be an acceleration specified for the origin of the joint.
geometry_msgs/Twist[] accelerations

# Desired time from the trajectory start to arrive at this trajectory point.
builtin_interfaces/Duration time_from_start

0 comments on commit ba32be2

Please sign in to comment.