Skip to content

Commit

Permalink
Merge pull request #194 from Kinovarobotics/bugfix/duplicate-prefix
Browse files Browse the repository at this point in the history
remove prefix that duplicates joint_state
  • Loading branch information
felixmaisonneuve authored Sep 17, 2021
2 parents a334ce2 + ac4150c commit 476faba
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion kortex_driver/readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ The `kortex_driver` node is the node responsible for the communication between t
- **vision** : Boolean value to indicate if your arm has a Vision Module. The default value is for Gen3 is **true** and the default value for Gen3 lite is **false**. You will have to specify this value only if you have a Gen3 6DOF without a Vision Module. This argument only affects the visual representation of the arm in RViz.
- **gripper** : Name of your robot arm's tool / gripper. See the `kortex_description/grippers` folder to see the available end effector models (or to add your own). The default value is **""**. For Gen3, you can also put **robotiq_2f_85** or **robotiq_2f_140**. For Gen3 lite, the default (and only) gripper is **gen3_lite_2f**.
- **robot_name** : This is the namespace in which the driver will run. It defaults to **my_$(arg arm)** (so "my_gen3" for arm="gen3").
- **prefix** : This is an optional prefix for all joint and link names in the kortex_description. It is used to allow differentiating between different arms in the same URDF. It defaults to **an empty string**. **Note** : Changing the prefix invalidates the MoveIt! configuration, and requires modifying said configuration, plus the .yaml files with harcoded joint names.
- **prefix** : This is an optional prefix for all joint and link names in the kortex_description. It is used to allow differentiating between different arms in the same URDF. It defaults to **an empty string**.
- **ip_address** : The IP address of the robot you're connecting to. The default value is **192.168.1.10**.
- **username** : The username for the robot connection. The default value is **admin**.
- **password** : The password for the robot connection. The default value is **admin**.
Expand Down
4 changes: 2 additions & 2 deletions kortex_driver/src/non-generated/driver/kortex_arm_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -652,7 +652,7 @@ void KortexArmDriver::publishRobotFeedback()

for (int i = 0; i < base_feedback.actuators.size(); i++)
{
joint_state.name[i] = m_prefix + m_arm_joint_names[i];
joint_state.name[i] = m_arm_joint_names[i];
joint_state.position[i] = m_math_util.wrapRadiansFromMinusPiToPi(m_math_util.toRad(base_feedback.actuators[i].position));
joint_state.velocity[i] = m_math_util.toRad(base_feedback.actuators[i].velocity);
joint_state.effort[i] = base_feedback.actuators[i].torque;
Expand All @@ -663,7 +663,7 @@ void KortexArmDriver::publishRobotFeedback()
for (int i = 0; i < base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor.size(); i++)
{
int joint_state_index = base_feedback.actuators.size() + i;
joint_state.name[joint_state_index] = m_prefix + m_gripper_joint_names[i];
joint_state.name[joint_state_index] = m_gripper_joint_names[i];
// Arm feedback is between 0 and 100, and limits in URDF are specified in gripper_joint_limits_min[i] and gripper_joint_limits_max[i] parameters
joint_state.position[joint_state_index] = m_math_util.absolute_position_from_relative(base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor[i].position / 100.0, m_gripper_joint_limits_min[i], m_gripper_joint_limits_max[i]);
joint_state.velocity[joint_state_index] = base_feedback.interconnect.oneof_tool_feedback.gripper_feedback[0].motor[i].velocity;
Expand Down

0 comments on commit 476faba

Please sign in to comment.