23 #include <sensor_msgs/JointState.h>
24 #include <control_msgs/JointTrajectoryControllerState.h>
25 #include <std_msgs/Float64.h>
26 #include <geometry_msgs/Twist.h>
29 #include <kdl/chainfksolvervel_recursive.hpp>
30 #include <kdl/chainjnttojacsolver.hpp>
31 #include <kdl/frames.hpp>
32 #include <kdl/jntarray.hpp>
33 #include <kdl/jntarrayvel.hpp>
35 #include <Eigen/Dense>
58 if (!
nh_.
getParam(
"chain_base_link", this->chain_base_link_))
60 ROS_ERROR(
"Failed to get parameter \"chain_base_link\".");
64 if (!
nh_.
getParam(
"chain_tip_link", this->chain_tip_link_))
66 ROS_ERROR(
"Failed to get parameter \"chain_tip_link\".");
74 ROS_ERROR(
"Failed to construct kdl tree");
78 my_tree.getChain(this->chain_base_link_, this->chain_tip_link_,
chain_);
79 if (
chain_.getNrOfJoints() == 0)
81 ROS_ERROR(
"Failed to initialize kinematic chain");
86 ROS_WARN(
"~~~~~~~~~~~~~ DEBUG CHAIN ~~~~~~~~~~~~~");
89 for (
unsigned int i = 0; i <
chain_.getNrOfSegments(); i++)
91 KDL::Segment segment =
chain_.getSegment(i);
93 KDL::Joint joint = segment.getJoint();
97 ROS_WARN(
"~~~~~~~~~~~~~ DEBUG CHAIN ~~~~~~~~~~~~~");
115 KDL::JntArray q = KDL::JntArray(
chain_.getNrOfJoints());
116 KDL::JntArray q_dot = KDL::JntArray(
chain_.getNrOfJoints());
119 for (
unsigned int i = 0; i <
chain_.getNrOfSegments(); i++)
121 KDL::Joint joint =
chain_.getSegment(i).getJoint();
122 std::string joint_name = joint.getName();
123 if (joint.getType() == KDL::Joint::None)
130 if (std::find(
msg->name.begin(),
msg->name.end(), joint_name) !=
msg->name.end())
132 unsigned int index = std::distance(
msg->name.begin(), std::find(
msg->name.begin(),
msg->name.end(), joint_name));
133 q(index) =
msg->position[index];
134 q_dot(index) =
msg->velocity[index];
145 std::vector< KDL::FrameVel > v_FrameVel;
146 KDL::JntArrayVel jntArrayVel = KDL::JntArrayVel(q, q_dot);
147 v_FrameVel.resize(
chain_.getNrOfSegments());
151 geometry_msgs::Twist twist_msg;
156 sensor_msgs::JointState magnitude_msg;
157 magnitude_msg.header.stamp =
msg->header.stamp;
158 for (
unsigned int i = 0; i <
chain_.getNrOfSegments(); i++)
160 magnitude_msg.name.push_back(
chain_.getSegment(i).getName());
161 magnitude_msg.velocity.push_back(v_FrameVel[i].GetTwist().vel.Norm());
167 KDL::Jacobian jac(
chain_.getNrOfJoints());
169 Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic> prod = jac.data * jac.data.transpose();
170 double d = prod.determinant();
171 double kappa = std::sqrt(std::abs(
d));
172 std_msgs::Float64 manipulability_msg;
173 manipulability_msg.data = kappa;
179 KDL::JntArray q_desired = KDL::JntArray(
chain_.getNrOfJoints());
180 KDL::JntArray q_desired_dot = KDL::JntArray(
chain_.getNrOfJoints());
181 KDL::JntArray q_actual = KDL::JntArray(
chain_.getNrOfJoints());
182 KDL::JntArray q_actual_dot = KDL::JntArray(
chain_.getNrOfJoints());
184 for (
unsigned int i = 0; i <
chain_.getNrOfSegments(); i++)
186 KDL::Joint joint =
chain_.getSegment(i).getJoint();
187 std::string joint_name = joint.getName();
188 if (joint.getType() == KDL::Joint::None)
195 if (std::find(
msg->joint_names.begin(),
msg->joint_names.end(), joint_name) !=
msg->joint_names.end())
197 unsigned int index = std::distance(
msg->joint_names.begin(), std::find(
msg->joint_names.begin(),
msg->joint_names.end(), joint_name));
198 q_desired(index) =
msg->desired.positions[index];
199 q_desired_dot(index) =
msg->desired.velocities[index];
200 q_actual(index) =
msg->actual.positions[index];
201 q_actual_dot(index) =
msg->actual.velocities[index];
205 ROS_ERROR_STREAM(
"Joint '" << joint_name <<
"' not found in JointTrajectoryControllerState");
212 std::vector< KDL::FrameVel > v_FrameVel_desired;
213 KDL::JntArrayVel jntArrayVel_desired = KDL::JntArrayVel(q_desired, q_desired_dot);
214 v_FrameVel_desired.resize(
chain_.getNrOfSegments());
215 if (
p_fksolver_vel_->JntToCart(jntArrayVel_desired, v_FrameVel_desired,
chain_.getNrOfSegments()) >= 0)
217 sensor_msgs::JointState magnitude_desired_msg;
218 magnitude_desired_msg.header.stamp =
msg->header.stamp;
219 for (
unsigned int i = 0; i <
chain_.getNrOfSegments(); i++)
221 magnitude_desired_msg.name.push_back(
chain_.getSegment(i).getName());
222 magnitude_desired_msg.velocity.push_back(v_FrameVel_desired[i].GetTwist().vel.Norm());
227 std::vector< KDL::FrameVel > v_FrameVel_actual;
228 KDL::JntArrayVel jntArrayVel_actual = KDL::JntArrayVel(q_actual, q_actual_dot);
229 v_FrameVel_actual.resize(
chain_.getNrOfSegments());
230 if (
p_fksolver_vel_->JntToCart(jntArrayVel_actual, v_FrameVel_actual,
chain_.getNrOfSegments()) >= 0)
232 sensor_msgs::JointState magnitude_actual_msg;
233 magnitude_actual_msg.header.stamp =
msg->header.stamp;
234 for (
unsigned int i = 0; i <
chain_.getNrOfSegments(); i++)
236 magnitude_actual_msg.name.push_back(
chain_.getSegment(i).getName());
237 magnitude_actual_msg.velocity.push_back(v_FrameVel_actual[i].GetTwist().vel.Norm());
246 int main(
int argc,
char** argv)
248 ros::init(argc, argv,
"debug_fk_vel_recursive_node");
251 if (dfvr.
init() != 0)
253 ROS_ERROR(
"Failed to initialize DebugFkVelRecursive.");