Skip to content

Commit

Permalink
Style and documentation fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
Kevin Allen committed Jul 17, 2018
1 parent 694f9d8 commit f491f8d
Show file tree
Hide file tree
Showing 16 changed files with 207 additions and 675 deletions.
Empty file removed gazebo_msgs/AMENT_IGNORE
Empty file.
32 changes: 16 additions & 16 deletions gazebo_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

set(msg_files
"msg/ContactsState.msg"
"msg/ContactState.msg"
"msg/ContactsState.msg"
"msg/LinkState.msg"
"msg/LinkStates.msg"
"msg/ModelState.msg"
Expand All @@ -33,28 +33,28 @@ set(msg_files

set(srv_files
"srv/ApplyBodyWrench.srv"
"srv/DeleteModel.srv"
"srv/DeleteLight.srv"
"srv/GetLinkState.srv"
"srv/GetPhysicsProperties.srv"
"srv/SetJointProperties.srv"
"srv/SetModelConfiguration.srv"
"srv/SpawnModel.srv"
"srv/ApplyJointEffort.srv"
"srv/GetJointProperties.srv"
"srv/GetModelProperties.srv"
"srv/GetWorldProperties.srv"
"srv/SetLinkProperties.srv"
"srv/SetModelState.srv"
"srv/BodyRequest.srv"
"srv/DeleteLight.srv"
"srv/DeleteModel.srv"
"srv/GetJointProperties.srv"
"srv/GetLightProperties.srv"
"srv/GetLinkProperties.srv"
"srv/GetLinkState.srv"
"srv/GetModelProperties.srv"
"srv/GetModelState.srv"
"srv/GetPhysicsProperties.srv"
"srv/GetWorldProperties.srv"
"srv/JointRequest.srv"
"srv/SetLinkState.srv"
"srv/SetPhysicsProperties.srv"
"srv/SetJointProperties.srv"
"srv/SetJointTrajectory.srv"
"srv/GetLightProperties.srv"
"srv/SetLightProperties.srv"
"srv/SetLinkProperties.srv"
"srv/SetLinkState.srv"
"srv/SetModelConfiguration.srv"
"srv/SetModelState.srv"
"srv/SetPhysicsProperties.srv"
"srv/SpawnModel.srv"
)

rosidl_generate_interfaces(${PROJECT_NAME}
Expand Down
4 changes: 2 additions & 2 deletions gazebo_msgs/msg/ODEJointProperties.msg
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# access to low level joint properties, change these at your own risk
float64[] damping # joint damping
float64[] hi_stop # joint limit
float64[] lo_stop # joint limit
float64[] hi_stop # joint limit
float64[] lo_stop # joint limit
float64[] erp # set joint erp
float64[] cfm # set joint cfm
float64[] stop_erp # set joint erp for joint limit "contact" joint
Expand Down
3 changes: 1 addition & 2 deletions gazebo_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,7 @@
Message and service data structures for interacting with Gazebo from ROS2.
</description>

<author>John Hsu</author>
<maintainer email="ecorbellini@ekumenlabs.com">Ernesto Corbellini</maintainer>
<maintainer email="jrivero@osrfoundation.org">Jose Luis Rivero</maintainer>

<license>BSD</license>

Expand Down
4 changes: 2 additions & 2 deletions gazebo_msgs/srv/ApplyBodyWrench.srv
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,10 @@ string reference_frame # wrench is defined in the reference f
# frame names are bodies prefixed by model name, e.g. pr2::base_link
geometry_msgs/Point reference_point # wrench is defined at this location in the reference frame
geometry_msgs/Wrench wrench # wrench applied to the origin of the body
builtin_interfaces/Time start_time # (optional) wrench application start time (seconds)
builtin_interfaces/Time start_time # (optional) wrench application start time (seconds)
# if start_time is not specified, or
# start_time < current time, start as soon as possible
builtin_interfaces/Duration duration # optional duration of wrench application time (seconds)
builtin_interfaces/Duration duratio # optional duration of wrench application time (seconds)
# if duration < 0, apply wrench continuously without end
# if duration = 0, do nothing
# if duration < step size, apply wrench
Expand Down
22 changes: 11 additions & 11 deletions gazebo_msgs/srv/ApplyJointEffort.srv
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
# set urdf joint effort
string joint_name # joint to apply wrench (linear force and torque)
float64 effort # effort to apply
builtin_interfaces/Time start_time # optional wrench application start time (seconds)
# if start_time < current time, start as soon as possible
builtin_interfaces/Duration duration # optional duration of wrench application time (seconds)
# if duration < 0, apply wrench continuously without end
# if duration = 0, do nothing
# if duration < step size, assume step size and
# display warning in status_message
string joint_name # joint to apply wrench (linear force and torque)
float64 effort # effort to apply
builtin_interfaces/Time start_time # optional wrench application start time (seconds)
# if start_time < current time, start as soon as possible
builtin_interfaces/Duration duration # optional duration of wrench application time (seconds)
# if duration < 0, apply wrench continuously without end
# if duration = 0, do nothing
# if duration < step size, assume step size and
# display warning in status_message
---
bool success # return true if effort application is successful
string status_message # comments if available
bool success # return true if effort application is successful
string status_message # comments if available
Loading

0 comments on commit f491f8d

Please sign in to comment.