00001
00002
00003
00004
00005
00006
00007
00008 #include <ros/ros.h>
00009
00010 #include "articulation_msgs/TrackMsg.h"
00011 #include "articulation_msgs/AlignModelSrv.h"
00012 #include "geometry_msgs/Pose.h"
00013 #include "LinearMath/btTransform.h"
00014
00015 #include "icp/icp_utils.h"
00016
00017 using namespace std;
00018 using namespace articulation_msgs;
00019 using namespace icp;
00020
00021
00022 bool icp_align(articulation_msgs::AlignModelSrv::Request &request,
00023 articulation_msgs::AlignModelSrv::Response &response
00024 )
00025 {
00026 ROS_INFO("aligning model with data, poses=%d, poses=%d", request.model.track.pose.size(),request.data.track.pose.size());
00027
00028 IcpAlign alignment(request.model.track, request.data.track);
00029 response.data_aligned = request.data;
00030 alignment.TransformData(response.data_aligned.track);
00031 response.model_aligned = request.model;
00032 alignment.TransformModel(response.model_aligned.track);
00033 for(int i=0;i<9;i++)
00034 response.R[i] = alignment.TR[i];
00035 for(int i=0;i<3;i++)
00036 response.T[i] = alignment.TT[i];
00037 btMatrix3x3 rot(
00038 alignment.TR[0],alignment.TR[1],alignment.TR[2],
00039 alignment.TR[3],alignment.TR[4],alignment.TR[5],
00040 alignment.TR[6],alignment.TR[7],alignment.TR[8]);
00041 btVector3 trans(alignment.TT[0],alignment.TT[1],alignment.TT[2]);
00042 btTransform diff(rot,trans);
00043 response.dist_trans = trans.length();
00044 response.dist_rot = diff.getRotation().getAngle();
00045 return true;
00046 }
00047
00048 int main(int argc, char** argv)
00049 {
00050 ros::init(argc, argv, "icp_test");
00051 ros::NodeHandle n;
00052
00053 ros::ServiceServer icp_align_service= n.advertiseService("icp_align", icp_align);
00054
00055 ROS_INFO("icp_align running, service ready");
00056 ros::spin();
00057 }