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

Added #define-based namespaces to prevent linking errors. #355

Open
wants to merge 4 commits into
base: kinetic-devel
Choose a base branch
from
Open
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
20 changes: 16 additions & 4 deletions ur_kinematics/include/ur_kinematics/ur_kin.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,16 @@
#ifndef UR_KIN_H
#define UR_KIN_H

#if defined UR10_PARAMS
#define UR_NAMESPACE ur10
#elif defined UR5_PARAMS
#define UR_NAMESPACE ur5
#elif defined UR3_PARAMS
#define UR_NAMESPACE ur3
#else
#error "You must #define which UR model you wish to use. Options are { UR10_PARAMS, UR5_PARAMS, UR3_PARAMS }."
#endif

// These kinematics find the tranfrom from the base link to the end effector.
// Though the raw D-H parameters specify a transform from the 0th link to the 6th link,
// offset transforms are specified in this formulation.
Expand All @@ -56,13 +66,14 @@
// 0, 0, 0, 1

namespace ur_kinematics {
// @param q The 6 joint values
namespace UR_NAMESPACE {
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If we make this an inline namespace, then we can keep API compatibility the same, so people don't need to add this extra namespace to their function calls.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Interesting idea. I wasn't familiar with inline namespace.

// @param q The 6 joint values
// @param T The 4x4 end effector pose in row-major ordering
void forward(const double* q, double* T);

// @param q The 6 joint values
// @param q The 6 joint values
// @param Ti The 4x4 link i pose in row-major ordering. If NULL, nothing is stored.
void forward_all(const double* q, double* T1, double* T2, double* T3,
void forward_all(const double* q, double* T1, double* T2, double* T3,
double* T4, double* T5, double* T6);

// @param T The 4x4 end effector pose in row-major ordering
Expand All @@ -71,6 +82,7 @@ namespace ur_kinematics {
// in case of an infinite solution on that joint.
// @return Number of solutions found (maximum of 8)
int inverse(const double* T, double* q_sols, double q6_des=0.0);
};
}
}

#endif //UR_KIN_H
2 changes: 1 addition & 1 deletion ur_kinematics/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package>
<name>ur_kinematics</name>
<version>1.2.1</version>
<version>1.3.0</version>
<description>
Provides forward and inverse kinematics for Universal Robots designs.
See http://hdl.handle.net/1853/50782 for details.
Expand Down
11 changes: 7 additions & 4 deletions ur_kinematics/src/ur_kin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ namespace ur_kinematics {
#endif
}

namespace UR_NAMESPACE {

void forward(const double* q, double* T) {
double s1 = sin(*q), c1 = cos(*q); q++;
double q234 = *q, s2 = sin(*q), c2 = cos(*q); q++;
Expand Down Expand Up @@ -348,6 +350,7 @@ namespace ur_kinematics {
}
return num_sols;
}
}
};


Expand Down Expand Up @@ -397,7 +400,7 @@ IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkRe

to_mat44(T, eetrans, eerot);

int num_sols = ur_kinematics::inverse(T, q_sols,pfree[0]);
int num_sols = ur_kinematics::UR_NAMESPACE::inverse(T, q_sols,pfree[0]);

std::vector<int> vfree(0);

Expand All @@ -412,7 +415,7 @@ IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkRe
IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot)
{
double T[16];
ur_kinematics::forward(j,T);
ur_kinematics::UR_NAMESPACE::forward(j,T);
from_mat44(T,eetrans,eerot);
}

Expand All @@ -435,15 +438,15 @@ int main(int argc, char* argv[])
{
double q[6] = {0.0, 0.0, 1.0, 0.0, 1.0, 0.0};
double* T = new double[16];
forward(q, T);
UR_NAMESPACE::forward(q, T);
for(int i=0;i<4;i++) {
for(int j=i*4;j<(i+1)*4;j++)
printf("%1.3f ", T[j]);
printf("\n");
}
double q_sols[8*6];
int num_sols;
num_sols = inverse(T, q_sols);
num_sols = UR_NAMESPACE::inverse(T, q_sols);
for(int i=0;i<num_sols;i++)
printf("%1.6f %1.6f %1.6f %1.6f %1.6f %1.6f\n",
q_sols[i*6+0], q_sols[i*6+1], q_sols[i*6+2], q_sols[i*6+3], q_sols[i*6+4], q_sols[i*6+5]);
Expand Down
4 changes: 2 additions & 2 deletions ur_kinematics/src/ur_moveit_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -643,8 +643,8 @@ bool URKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose &ik_pose,
/////////////////////////////////////////////////////////////////////////////

// Do the analytic IK
num_sols = inverse((double*) homo_ik_pose, (double*) q_ik_sols,
jnt_pos_test(ur_joint_inds_start_+5));
num_sols = UR_NAMESPACE::inverse((double*) homo_ik_pose, (double*) q_ik_sols,
jnt_pos_test(ur_joint_inds_start_+5));


uint16_t num_valid_sols;
Expand Down