-
Notifications
You must be signed in to change notification settings - Fork 165
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
Move arm inbound on init #184
Changes from 3 commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -49,6 +49,7 @@ KortexArmDriver::KortexArmDriver(ros::NodeHandle nh): m_node_handle(nh), | |
if (m_is_real_robot) | ||
{ | ||
m_publish_feedback_thread = std::thread(&KortexArmDriver::publishRobotFeedback, this); | ||
moveArmWithinJointLimits(); | ||
} | ||
else | ||
{ | ||
|
@@ -526,6 +527,69 @@ void KortexArmDriver::startActionServers() | |
} | ||
} | ||
|
||
void KortexArmDriver::moveArmWithinJointLimits() | ||
{ | ||
auto joint_angles = m_base->GetMeasuredJointAngles(); | ||
|
||
std::map<int, float> limited_joints; | ||
if (m_degrees_of_freedom == 6) | ||
{ | ||
// We add angle limitations for joints 1,2 and 4 on 6 dof | ||
limited_joints[1] = 128.9; | ||
limited_joints[2] = 147.8; | ||
limited_joints[4] = 120.3; | ||
} | ||
else | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
|
||
{ | ||
// We add angle limitations for joints 1,3 and 5 on 7 dof | ||
limited_joints[1] = 128.9; | ||
limited_joints[3] = 147.8; | ||
limited_joints[5] = 120.3; | ||
} | ||
|
||
Kinova::Api::Base::JointSpeeds joint_speeds = Kinova::Api::Base::JointSpeeds(); | ||
Kinova::Api::Base::JointSpeed* joint_speed = joint_speeds.add_joint_speeds(); | ||
|
||
static const int TIME_COMPENSATION = 100; | ||
static const int DEFAULT_JOINT_SPEED = 10; | ||
static const int TIME_SPEED_RATIO = 1000 / DEFAULT_JOINT_SPEED; | ||
|
||
float angle; | ||
for (unsigned int i = 0; i < m_degrees_of_freedom; i++) | ||
{ | ||
angle = joint_angles.joint_angles(i).value(); | ||
|
||
// Angles received by GetMeasuredJointAngles are in range [0,360], but waypoints are in range [-180, 180] | ||
angle = m_math_util.toDeg(m_math_util.wrapRadiansFromMinusPiToPi(m_math_util.toRad(angle))); | ||
|
||
if(limited_joints.find(i) != limited_joints.end()) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I find |
||
{ | ||
float delta = m_math_util.findDeltaFromBoundaries(angle, limited_joints.at(i)); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. this function returns a |
||
|
||
if (delta != 0) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. be careful for float equality, should probably check for |
||
{ | ||
// we add some time to compensate acceleration | ||
int time_ms = delta * TIME_SPEED_RATIO + TIME_COMPENSATION; | ||
int speed = DEFAULT_JOINT_SPEED; | ||
joint_speed->set_joint_identifier(i); | ||
|
||
if (angle > 0) | ||
{ | ||
speed *= -1; | ||
} | ||
|
||
joint_speed->set_value(speed); | ||
m_base->SendJointSpeedsCommand(joint_speeds); | ||
|
||
std::this_thread::sleep_for(std::chrono::milliseconds(time_ms)); | ||
|
||
joint_speed->set_value(0); | ||
m_base->SendJointSpeedsCommand(joint_speeds); | ||
} | ||
} | ||
} | ||
} | ||
|
||
bool KortexArmDriver::isGripperPresent() | ||
{ | ||
return m_gripper_name != ""; | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -100,6 +100,18 @@ double KortexMathUtil::absolute_position_from_relative(double relative_position, | |
return relative_position * range + min_value; | ||
} | ||
|
||
double KortexMathUtil::findDeltaFromBoundaries(double value, double limit) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. could rename to something more verbose like |
||
{ | ||
double delta = std::abs(value) - limit; | ||
|
||
if ( delta < 0 ) | ||
{ | ||
delta = 0; | ||
} | ||
|
||
return delta; | ||
} | ||
|
||
kortex_driver::Twist KortexMathUtil::substractTwists(const kortex_driver::Twist& a, const kortex_driver::Twist& b) | ||
{ | ||
kortex_driver::Twist c; | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
is there a variable holding these values? instead of magic numbers?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I don't think so. I got them from the User Guide, p.86.