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

clean all trailing whitespace in definitions #134

Merged
merged 1 commit into from
Oct 3, 2021
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
2 changes: 1 addition & 1 deletion action/Place.action
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ string attached_object_name
# a list of possible transformations for placing the object
PlaceLocation[] place_locations

# if the user prefers setting the eef pose (same as in pick) rather than
# if the user prefers setting the eef pose (same as in pick) rather than
# the location of the object, this flag should be set to true
bool place_eef

Expand Down
6 changes: 3 additions & 3 deletions dox/definePlanningRequest.dox
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ The content of this message may look intimidating, but most of its fields are op
- \b group_name This is the name of the group to plan for. This member is required and must be a group name defined in the SRDF.
- \b start_state This is the state to assume the robot starts at. This member does not need to be specified. Joint values that are not
set in this message are assumed to be the same as the robot's \e current state (as specified by the PlanningScene visible to the planner).
- \b goal_constraints Instead of defining a goal state, goals are specified in a more generic fashion: in terms of constraints. Constraints
- \b goal_constraints Instead of defining a goal state, goals are specified in a more generic fashion: in terms of constraints. Constraints
can be very specific, to defining a bounding box in the joint space of the robot such that only one goal state is included, to being very generic,
where a link of the robot (e.g., the end-effector) is required to move to some specified volume of the space. There can be multiple goal constraints
specified. Each goal constraint is considered a possible goal. The planner will try to find a path that reaches a state that satisfies at least one of the specified goal constraints. However, all the sub-constraints specified withing a Constraints message must be satisfied.
Expand All @@ -35,9 +35,9 @@ the library will use the planning algorithm identified by the specified planner_
The request to this service is simply a motion planning request as described above.
The result includes the following members:
- \b trajectory These are the points along the solution path. Only joints for the group planned for are included.
- \b trajectory_start The computed thajectory does not include all robot joints; as such, the trajectory is not complete,
- \b trajectory_start The computed thajectory does not include all robot joints; as such, the trajectory is not complete,
since we do not know the values for the links that were not included in planning. For this reason, the full robot state is included.
This state is usually the robot's current state (as in the planning scene set for planning), but with values specified by the
This state is usually the robot's current state (as in the planning scene set for planning), but with values specified by the
\e start_state overwritten.
- \b planning_time This is the amount of time the planner took to compute the motion plan
- \b error_code The status code reported after planning.
Expand Down
4 changes: 2 additions & 2 deletions msg/AllowedCollisionMatrix.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@ string[] entry_names
# square, symmetric, with same order as entry_names
AllowedCollisionEntry[] entry_values

# In addition to the collision matrix itself, we also have
# In addition to the collision matrix itself, we also have
# the default entry value for each entry name.

# If the allowed collision flag is queried for a pair of names (n1, n2)
# that is not found in the collision matrix itself, the value of
# the collision flag is considered to be that of the entry (n1 or n2)
# specified in the list below. If both n1 and n2 are found in the list
# specified in the list below. If both n1 and n2 are found in the list
# of defaults, the result is computed with an AND operation

string[] default_entry_names
Expand Down
2 changes: 1 addition & 1 deletion msg/AttachedCollisionObject.msg
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ CollisionObject object
# by default - the link_name is already considered by default
string[] touch_links

# If certain links were placed in a particular posture for this object to remain attached
# If certain links were placed in a particular posture for this object to remain attached
# (e.g., an end effector closing around an object), the posture necessary for releasing
# the object is stored here
trajectory_msgs/JointTrajectory detach_posture
Expand Down
2 changes: 1 addition & 1 deletion msg/ConstraintEvalResult.msg
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# This message contains result from constraint evaluation
# result specifies the result of constraint evaluation
# result specifies the result of constraint evaluation
# (true indicates state satisfies constraint, false indicates state violates constraint)
# if false, distance specifies a measure of the distance of the state from the constraint
# if true, distance is set to zero
Expand Down
6 changes: 3 additions & 3 deletions msg/ContactInformation.msg
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
# Standard ROS header contains information
# about the frame in which this
# Standard ROS header contains information
# about the frame in which this
# contact is specified
Header header

# Position of the contact point
geometry_msgs/Point position

# Normal corresponding to the contact point
geometry_msgs/Vector3 normal
geometry_msgs/Vector3 normal

# Depth of contact point
float64 depth
Expand Down
2 changes: 1 addition & 1 deletion msg/Grasp.msg
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ GripperTranslation post_grasp_retreat
# The retreat motion to perform when releasing the object; this information
# is not necessary for the grasp itself, but when releasing the object,
# the information will be necessary. The grasp used to perform a pickup
# is returned as part of the result, so this information is available for
# is returned as part of the result, so this information is available for
# later use.
GripperTranslation post_place_retreat

Expand Down
2 changes: 1 addition & 1 deletion msg/MotionPlanDetailedResponse.msg
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ RobotTrajectory[] trajectory
# Description of the reported trajectories (name of processing step)
string[] description

# The amount of time spent computing a particular step in motion plan computation
# The amount of time spent computing a particular step in motion plan computation
float64[] processing_time

# Status at the end of this plan
Expand Down
2 changes: 1 addition & 1 deletion msg/PlaceLocation.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ string id
# positions and efforts are used
trajectory_msgs/JointTrajectory post_place_posture

# The position of the end-effector for the grasp relative to a reference frame
# The position of the end-effector for the grasp relative to a reference frame
# (that is always specified elsewhere, not in this message)
geometry_msgs/PoseStamped place_pose

Expand Down
10 changes: 5 additions & 5 deletions msg/PlanningOptions.msg
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
PlanningScene planning_scene_diff

# If this flag is set to true, the action
# returns an executable plan in the response but does not attempt execution
# returns an executable plan in the response but does not attempt execution
bool plan_only

# If this flag is set to true, the action of planning &
Expand All @@ -20,17 +20,17 @@ int32 look_around_attempts

# If set and if look_around is true, this value is used as
# the maximum cost allowed for a path to be considered executable.
# If the cost of a path is higher than this value, more sensing or
# a new plan needed. If left as 0.0 but look_around is true, then
# If the cost of a path is higher than this value, more sensing or
# a new plan needed. If left as 0.0 but look_around is true, then
# the default value set via dynamic_reconfigure is used
float64 max_safe_execution_cost

# If the plan becomes invalidated during execution, it is possible to have
# that plan recomputed and execution restarted. This flag enables this
# functionality
# functionality
bool replan

# The maximum number of replanning attempts
# The maximum number of replanning attempts
int32 replan_attempts

# The amount of time to wait in between replanning attempts (in seconds)
Expand Down
2 changes: 1 addition & 1 deletion msg/PlanningScene.msg
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ LinkPadding[] link_padding
# all link scales
LinkScale[] link_scale

# Attached objects, collision objects, even the octomap or collision map can have
# Attached objects, collision objects, even the octomap or collision map can have
# colors associated to them. This array specifies them.
ObjectColor[] object_colors

Expand Down
2 changes: 1 addition & 1 deletion msg/PlanningSceneComponents.msg
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ uint32 WORLD_OBJECT_NAMES=8
# The geometry of the world objects
uint32 WORLD_OBJECT_GEOMETRY=16

# The maintained octomap
# The maintained octomap
uint32 OCTOMAP=32

# The maintained list of transforms
Expand Down
2 changes: 1 addition & 1 deletion msg/PositionConstraint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ string link_name
# The offset (in the link frame) for the target point on the link we are planning for
geometry_msgs/Vector3 target_point_offset

# The volume this constraint refers to
# The volume this constraint refers to
BoundingVolume constraint_region

# A weighting factor for this constraint (denotes relative importance to other constraints. Closer to zero means less important)
Expand Down
14 changes: 7 additions & 7 deletions msg/PositionIKRequest.msg
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,15 @@

# The name of the group which will be used to compute IK
# e.g. "right_arm", or "arms" - see IK specification for multiple-groups below
# Information from the SRDF will be used to automatically determine which link
# Information from the SRDF will be used to automatically determine which link
# to solve IK for, unless ik_link_name is also specified
string group_name

# A RobotState consisting of hint/seed positions for the IK computation and positions
# for all the other joints in the robot. Additional state information provided here is
# used to specify starting positions for other joints/links on the robot.
# A RobotState consisting of hint/seed positions for the IK computation and positions
# for all the other joints in the robot. Additional state information provided here is
# used to specify starting positions for other joints/links on the robot.
# This state MUST contain state for all joints to be used by the IK solver
# to compute IK. The list of joints that the IK solver deals with can be
# to compute IK. The list of joints that the IK solver deals with can be
# found using the SRDF for the corresponding group
moveit_msgs/RobotState robot_state

Expand All @@ -21,7 +21,7 @@ Constraints constraints
bool avoid_collisions

# (OPTIONAL) The name of the link for which we are computing IK
# If not specified, the link name will be inferred from a combination
# If not specified, the link name will be inferred from a combination
# of the group name and the SRDF. If any values are specified for ik_link_names,
# this value is ignored
string ik_link_name
Expand All @@ -34,7 +34,7 @@ geometry_msgs/PoseStamped pose_stamped
# Multi-group parameters

# (OPTIONAL) The names of the links for which we are computing IK
# If not specified, the link name will be inferred from a combination
# If not specified, the link name will be inferred from a combination
# of the group name and the SRDF
string[] ik_link_names

Expand Down
8 changes: 4 additions & 4 deletions msg/VisibilityConstraint.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,15 +6,15 @@
# and the target, nor does it enforce the target to be in the field of view of
# the sensor. A PositionConstraint can (and probably should) be used for such purposes.

# The radius of the disc that should be maintained visible
# The radius of the disc that should be maintained visible
float64 target_radius

# The pose of the disc; as the robot moves, the pose of the disc may change as well
# This can be in the frame of a particular robot link, for example
geometry_msgs/PoseStamped target_pose

# From the sensor origin towards the target, the disc forms a visibility cone
# This cone is approximated using many sides. For example, when using 4 sides,
# This cone is approximated using many sides. For example, when using 4 sides,
# that in fact makes the visibility region be a pyramid.
# This value should always be 3 or more.
int32 cone_sides
Expand All @@ -28,12 +28,12 @@ geometry_msgs/PoseStamped sensor_pose

# Even though the disc is maintained visible, the visibility cone can be very small
# because of the orientation of the disc with respect to the sensor. It is possible
# for example to view the disk almost from a side, in which case the visibility cone
# for example to view the disk almost from a side, in which case the visibility cone
# can end up having close to 0 volume. The view angle is defined to be the angle between
# the normal to the visibility disc and the direction vector from the sensor origin.
# The value below represents the minimum desired view angle. For a perfect view,
# this value will be 0 (the two vectors are exact opposites). For a completely obstructed view
# this value will be Pi/2 (the vectors are perpendicular). This value defined below
# this value will be Pi/2 (the vectors are perpendicular). This value defined below
# is the maximum view angle to be maintained. This should be a value in the open interval
# (0, Pi/2). If 0 is set, the view angle is NOT enforced.
float64 max_view_angle
Expand Down
2 changes: 1 addition & 1 deletion msg/WorkspaceParameters.msg
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# This message contains a set of parameters useful in
# setting up the volume (a box) in which the robot is allowed to move.
# This is useful only when planning for mobile parts of
# This is useful only when planning for mobile parts of
# the robot as well.

# Define the frame of reference for the box corners
Expand Down
2 changes: 1 addition & 1 deletion srv/ExecuteKnownTrajectory.srv
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# This service is deprecated and will go away at some point. For new development use the ExecuteTrajectory action.
# Effective since: Indigo 0.7.4, Jade and Kinetic 0.8.3

# The trajectory to execute
# The trajectory to execute
RobotTrajectory trajectory

# Set this to true if the service should block until the execution is complete
Expand Down
2 changes: 1 addition & 1 deletion srv/GetPositionFK.srv
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
# A service definition for a standard forward kinematics service
# The frame_id in the header message is the frame in which
# The frame_id in the header message is the frame in which
# the forward kinematics poses will be returned
Header header

Expand Down
2 changes: 1 addition & 1 deletion srv/GetPositionIK.srv
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ PositionIKRequest ik_request

---

# The returned solution
# The returned solution
# (in the same order as the list of joints specified in the IKRequest message)
RobotState solution

Expand Down