Skip to content

Commit 4437f4d

Browse files
authored
add joint velocity controller messages (#86)
1 parent 203da34 commit 4437f4d

File tree

3 files changed

+38
-0
lines changed

3 files changed

+38
-0
lines changed

moveit_studio_msgs/moveit_pro_controllers_msgs/CMakeLists.txt

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,11 @@ rosidl_generate_interfaces(
1919
"action/FollowJointTrajectoryWithAdmittance.action"
2020
"msg/AdmittanceParameters.msg"
2121
"msg/CartesianSelectionVector.msg"
22+
"msg/JointVelocityControllerState.msg"
2223
"msg/VelocityForceCommand.msg"
2324
"msg/VelocityForceControllerState.msg"
2425
"srv/ConfigureVelocityForceController.srv"
26+
"srv/ConfigureJointVelocityController.srv"
2527
DEPENDENCIES
2628
action_msgs
2729
builtin_interfaces
Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
# This message contains information about the internal state of the JointVelocityController.
2+
3+
# Timestamps associated to this state.
4+
std_msgs/Header header
5+
6+
# Joint names associated to the controller.
7+
# The order of the names is the same as the order of the joint positions, velocities and accelerations.
8+
string[] joint_names
9+
10+
# The reference joint-space positions, velocities and accelerations, as computed by the setpoint generator.
11+
float64[] reference_joint_positions
12+
float64[] reference_joint_velocities
13+
float64[] reference_joint_accelerations
14+
15+
# The current joint-space positions, velocities and accelerations, reported by the HW interface, or estimated internally.
16+
float64[] joint_positions
17+
float64[] joint_velocities
18+
float64[] joint_accelerations
Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
# Interface for configuring a joint velocity controller.
2+
# The configuration service will first load the configuration from the parameter server, and then override the fields
3+
# that are present in this request.
4+
# An empty request will reset the configuration to the default values (or those present in the parameter server).
5+
6+
# Joint velocity and acceleration limits.
7+
bool set_joint_velocity_limits
8+
float64[] joint_velocity_limits
9+
10+
bool set_joint_acceleration_limits
11+
float64[] joint_acceleration_limits
12+
13+
---
14+
# True if the configuration was successfully set.
15+
bool success
16+
17+
# Error message if success is false.
18+
string error_message

0 commit comments

Comments
 (0)