00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00038 #include "play_motion/play_motion_helpers.h"
00039 #include <cassert>
00040
00041 #include <ros/ros.h>
00042 #include <boost/foreach.hpp>
00043 #include "play_motion/xmlrpc_helpers.h"
00044 #define foreach BOOST_FOREACH
00045
00046 namespace play_motion
00047 {
00048 ros::NodeHandle getMotionsNodeHandle(const ros::NodeHandle& nh)
00049 {
00050 return ros::NodeHandle(nh, "motions");
00051 }
00052
00053 void extractTrajectory(xh::Array &traj_points, Trajectory& motion_points)
00054 {
00055
00056 motion_points.clear();
00057 motion_points.reserve(traj_points.size());
00058 for (int i = 0; i < traj_points.size(); ++i)
00059 {
00060 xh::Struct &name_value = traj_points[i];
00061 TrajPoint point;
00062 double tfs;
00063 xh::getStructMember(name_value, "time_from_start", tfs);
00064 point.time_from_start = ros::Duration(tfs);
00065
00066 xh::Array positions;
00067 xh::getStructMember(name_value, "positions", positions);
00068 point.positions.resize(positions.size());
00069 for (int j = 0; j < positions.size(); ++j)
00070 xh::getArrayItem(positions, j, point.positions[j]);
00071
00072 if (name_value.hasMember("velocities"))
00073 {
00074 xh::Array velocities;
00075 xh::getStructMember(name_value, "velocities", velocities);
00076 point.velocities.resize(velocities.size());
00077 for (int j = 0; j < velocities.size(); ++j)
00078 xh::getArrayItem(velocities, j, point.velocities[j]);
00079 }
00080 motion_points.push_back(point);
00081 }
00082 }
00083
00084 void extractJoints(xh::Array &joint_names, JointNames &motion_joints)
00085 {
00086 motion_joints.clear();
00087 motion_joints.resize(joint_names.size());
00088 for (int i = 0; i < joint_names.size(); ++i)
00089 xh::getArrayItem(joint_names, i, motion_joints[i]);
00090 }
00091
00092 void getMotionJoints(const ros::NodeHandle &nh, const std::string& motion_id,
00093 JointNames& motion_joints)
00094 {
00095 MotionInfo info;
00096 getMotion(nh, motion_id, info);
00097 motion_joints = info.joints;
00098 }
00099
00100 void getMotionJoints(const std::string& motion_id, JointNames& motion_joints)
00101 {
00102 ros::NodeHandle pm_nh("play_motion");
00103 getMotionJoints(pm_nh, motion_id, motion_joints);
00104 }
00105
00106 void getMotionPoints(const ros::NodeHandle &nh, const std::string& motion_id,
00107 Trajectory& motion_points)
00108 {
00109 MotionInfo info;
00110 getMotion(nh, motion_id, info);
00111 motion_points = info.traj;
00112 }
00113
00114 void getMotionPoints(const std::string& motion_id, Trajectory& motion_points)
00115 {
00116 ros::NodeHandle pm_nh("play_motion");
00117 getMotionPoints(pm_nh, motion_id, motion_points);
00118 }
00119
00120 void getMotionIds(const ros::NodeHandle &nh, MotionNames& motion_ids)
00121 {
00122 xh::Struct motions;
00123
00124 xh::fetchParam(nh, "motions/", motions);
00125 for (xh::Struct::iterator it = motions.begin(); it != motions.end(); ++it)
00126 {
00127 motion_ids.push_back(it->first);
00128 }
00129 }
00130
00131 void getMotionIds(MotionNames& motion_ids)
00132 {
00133 ros::NodeHandle pm_nh("play_motion");
00134 getMotionIds(pm_nh, motion_ids);
00135 }
00136
00137 void populateVelocities(const TrajPoint& point_prev,
00138 const TrajPoint& point_next,
00139 TrajPoint& point_curr)
00140 {
00141 const int num_joints = point_curr.positions.size();
00142 assert(num_joints == point_prev.positions.size() && num_joints == point_next.positions.size());
00143
00144
00145 if (int(point_curr.velocities.size()) == num_joints) {return;}
00146
00147
00148 std::vector<double>& vel_out = point_curr.velocities;
00149 vel_out.resize(num_joints, 0.0);
00150
00151
00152 for (int i = 0; i < num_joints; ++i)
00153 {
00154 const double pos_curr = point_curr.positions[i];
00155 const double pos_prev = point_prev.positions[i];
00156 const double pos_next = point_next.positions[i];
00157
00158 if ( (pos_curr == pos_prev) ||
00159 (pos_curr < pos_prev && pos_curr <= pos_next) ||
00160 (pos_curr > pos_prev && pos_curr >= pos_next) )
00161 {
00162 vel_out[i] = 0.0;
00163 }
00164 else
00165 {
00166
00167 const double t_prev = point_curr.time_from_start.toSec() - point_prev.time_from_start.toSec();
00168 const double t_next = point_next.time_from_start.toSec() - point_curr.time_from_start.toSec();
00169
00170 const double v_prev = (pos_curr - pos_prev)/t_prev;
00171 const double v_next = (pos_next - pos_curr)/t_next;
00172
00173 vel_out[i] = 0.5 * (v_prev + v_next);
00174 }
00175 }
00176 }
00177
00178 void populateVelocities(const Trajectory& traj_in, Trajectory& traj_out)
00179 {
00180 if (traj_in.empty()) {return;}
00181
00182 const int num_waypoints = traj_in.size();
00183 const int num_joints = traj_in.front().positions.size();
00184
00185
00186 TrajPoint& point_first = traj_out.front();
00187 TrajPoint& point_last = traj_out.back();
00188
00189 if (int(point_first.velocities.size()) != num_joints) {point_first.velocities.resize(num_joints, 0.0);}
00190 if (int(point_last.velocities.size()) != num_joints) {point_last.velocities.resize(num_joints, 0.0);}
00191
00192
00193 for (int i = 1; i < num_waypoints - 1; ++i) {populateVelocities(traj_in[i - 1], traj_in[i + 1], traj_out[i]);}
00194 }
00195
00196 ros::Duration getMotionDuration(const ros::NodeHandle &nh, const std::string &motion_id)
00197 {
00198 Trajectory traj;
00199 getMotionPoints(nh, motion_id, traj);
00200
00201 return traj.back().time_from_start;
00202 }
00203
00204 ros::Duration getMotionDuration(const std::string &motion_id)
00205 {
00206 ros::NodeHandle pm_nh("play_motion");
00207 return getMotionDuration(pm_nh, motion_id);
00208 }
00209
00210 bool motionExists(const ros::NodeHandle &nh, const std::string &motion_id)
00211 {
00212 try
00213 {
00214 ros::NodeHandle motions_nh = getMotionsNodeHandle(nh);
00215 return motions_nh.hasParam(motion_id + "/joints") && motions_nh.hasParam(motion_id + "/points");
00216 }
00217 catch (const ros::InvalidNameException&)
00218 {
00219 return false;
00220 }
00221 }
00222
00223 bool motionExists(const std::string &motion_id)
00224 {
00225 ros::NodeHandle pm_nh("play_motion");
00226 return motionExists(pm_nh, motion_id);
00227 }
00228
00229 bool isAlreadyThere(const JointNames &target_joints, const TrajPoint &target_point,
00230 const JointNames &source_joints, const TrajPoint &source_point,
00231 double tolerance)
00232 {
00233 if (target_joints.size() != target_point.positions.size())
00234 throw ros::Exception("targetJoint and targetPoint positions sizes do not match");
00235
00236 if (source_joints.size() != source_point.positions.size())
00237 throw ros::Exception("sourceJoint and sourcePoint positions sizes do not match");
00238
00239 for (int tIndex = 0; tIndex < target_joints.size(); ++tIndex)
00240 {
00241 JointNames::const_iterator it = std::find(source_joints.begin(), source_joints.end(),
00242 target_joints[tIndex]);
00245 if (it == source_joints.end())
00246 return false;
00247
00248 int sIndex = it - source_joints.begin();
00249 if (std::fabs(target_point.positions[tIndex] - source_point.positions[sIndex]) > tolerance)
00250 return false;
00251 }
00252 return true;
00253 }
00254
00255 void getMotion(const ros::NodeHandle &nh, const std::string &motion_id,
00256 MotionInfo &motion_info)
00257 {
00258 if (!motionExists(nh, motion_id))
00259 {
00260 const std::string what = "Motion '" + motion_id + "' does not exist or is malformed " +
00261 "(namespace " + getMotionsNodeHandle(nh).getNamespace() + ").";
00262 throw ros::Exception(what);
00263 }
00264 motion_info.id = motion_id;
00265 xh::Struct param;
00266 xh::fetchParam(getMotionsNodeHandle(nh), motion_id, param);
00267
00268 extractTrajectory(param["points"], motion_info.traj);
00269 extractJoints(param["joints"], motion_info.joints);
00270 if (param.hasMember("meta"))
00271 {
00272 xh::getStructMember(param["meta"], "description", motion_info.description);
00273 xh::getStructMember(param["meta"], "name", motion_info.name);
00274 xh::getStructMember(param["meta"], "usage", motion_info.usage);
00275 }
00276 else
00277 {
00278 motion_info.description = "";
00279 motion_info.name = "";
00280 motion_info.usage = "";
00281 }
00282 }
00283
00284 void getMotion(const std::string &motion_id, MotionInfo &motion_info)
00285 {
00286 ros::NodeHandle pm_nh("play_motion");
00287 play_motion::getMotion(pm_nh, motion_id, motion_info);
00288 }
00289
00290 }