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

missing prefix in driver #173

Merged
merged 1 commit into from
Jul 20, 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
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 @@ -514,15 +514,15 @@ void KortexArmDriver::initRosServices()
void KortexArmDriver::startActionServers()
{
// Start Action servers
m_action_server_follow_joint_trajectory = new JointTrajectoryActionServer(m_arm_name + "_joint_trajectory_controller/follow_joint_trajectory", m_node_handle, m_base, m_base_cyclic, m_control_config, m_use_hard_limits);
m_action_server_follow_joint_trajectory = new JointTrajectoryActionServer(m_prefix + m_arm_name + "_joint_trajectory_controller/follow_joint_trajectory", m_node_handle, m_base, m_base_cyclic, m_control_config, m_use_hard_limits);
// Start Gripper Action Server if the arm has a gripper

m_action_server_follow_cartesian_trajectory = new CartesianTrajectoryActionServer("cartesian_trajectory_controller/follow_cartesian_trajectory", m_node_handle, m_base, m_base_cyclic);

m_action_server_gripper_command = nullptr;
if (isGripperPresent())
{
m_action_server_gripper_command = new RobotiqGripperCommandActionServer(m_gripper_name + "_gripper_controller/gripper_cmd", m_gripper_joint_names[0], m_gripper_joint_limits_min[0], m_gripper_joint_limits_max[0], m_node_handle, m_base, m_base_cyclic);
m_action_server_gripper_command = new RobotiqGripperCommandActionServer(m_prefix + m_gripper_name + "_gripper_controller/gripper_cmd", m_gripper_joint_names[0], m_gripper_joint_limits_min[0], m_gripper_joint_limits_max[0], m_node_handle, m_base, m_base_cyclic);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -588,7 +588,7 @@ void KortexArmSimulation::CreateDefaultActions()
kortex_driver::JointAngle a;
a.joint_identifier = i;
auto named_target = m_moveit_arm_interface->getNamedTargetValues("retract");
double moveit_angle = named_target["joint_"+std::to_string(i+1)]; // rad
double moveit_angle = named_target[m_prefix + "joint_"+std::to_string(i+1)]; // rad
a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle));
retract_angles.joint_angles.joint_angles.push_back(a);
}
Expand All @@ -603,7 +603,7 @@ void KortexArmSimulation::CreateDefaultActions()
kortex_driver::JointAngle a;
a.joint_identifier = i;
auto named_target = m_moveit_arm_interface->getNamedTargetValues("home");
double moveit_angle = named_target["joint_"+std::to_string(i+1)]; // rad
double moveit_angle = named_target[m_prefix + "joint_"+std::to_string(i+1)]; // rad
a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle));
home_angles.joint_angles.joint_angles.push_back(a);
}
Expand All @@ -618,7 +618,7 @@ void KortexArmSimulation::CreateDefaultActions()
kortex_driver::JointAngle a;
a.joint_identifier = i;
auto named_target = m_moveit_arm_interface->getNamedTargetValues("vertical");
double moveit_angle = named_target["joint_"+std::to_string(i+1)]; // rad
double moveit_angle = named_target[m_prefix + "joint_"+std::to_string(i+1)]; // rad
a.value = m_math_util.wrapDegreesFromZeroTo360(m_math_util.toDeg(moveit_angle));
zero_angles.joint_angles.joint_angles.push_back(a);
}
Expand Down