Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #include "uos_rotunit_snapshotter.h"
00025
00026 RotunitSnapshotter::RotunitSnapshotter(ros::NodeHandle& nh, std::string action_name)
00027 : nh_(nh),
00028 action_name_(action_name),
00029 started_(false),
00030 server_(nh_, action_name_, boost::bind(&RotunitSnapshotter::makeSnapshot, this, _1), false)
00031 {
00032 ros::NodeHandle nh_private("~");
00033 nh_private.param("rotation_angle", rotation_angle , 2*M_PI);
00034 nh_private.param("continuous", continuous, true);
00035
00036 ROS_INFO("rotation angle is %f and continuous is %s", rotation_angle, continuous ? "true" : "false");
00037
00038 client_ = nh_.serviceClient<laser_assembler::AssembleScans2>("assemble_scans2");
00039 cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud2> ("assembled_cloud", 1);
00040 snapshot_pub_ = nh_.advertise<uos_rotunit_snapshotter::RotunitSnapshot> ("snapshot", 1);
00041 server_.start();
00042 if(continuous)
00043 state_sub_ = nh_.subscribe("joint_states", 1000, &RotunitSnapshotter::rotCallback, this);
00044 ROS_INFO("%s action server is running...", action_name_.c_str());
00045 }
00046
00047 double RotunitSnapshotter::norm2PI(double angle){
00048 while(angle < 0)
00049 angle += 2 * M_PI;
00050 while(angle > 2 * M_PI)
00051 angle -= 2 * M_PI;
00052 return angle;
00053 }
00054
00055 int RotunitSnapshotter::getIndex(const sensor_msgs::JointState::ConstPtr &jointState){
00056 for (size_t i = 0; i < jointState->name.size(); ++i)
00057 {
00058 if (jointState->name[i] == "laser_rot_joint")
00059 return i;
00060 }
00061 return -1;
00062 }
00063
00064 bool RotunitSnapshotter::checkIfFinished(double current_rot, ros::Time stamp){
00065 double current_rot_norm = norm2PI(current_rot);
00066
00067 if(!started_){
00068 begin_angle = current_rot_norm;
00069 begin_stamp = stamp;
00070 previous_rot = current_rot_norm;
00071 residual_rot = rotation_angle;
00072 destination_rot = norm2PI(current_rot_norm + rotation_angle);
00073 started_ = true;
00074 ROS_INFO("Start snapshot at %f degree, the destination angle is %f, angle aim is %f",
00075 current_rot_norm * 180.0 / M_PI, rotation_angle * 180.0 / M_PI, destination_rot * 180.0 / M_PI);
00076 }
00077 double diff = norm2PI(current_rot_norm - previous_rot);
00078 if(diff > M_PI / 180.0 && diff <= MAX_STEP_SIZE)
00079 residual_rot -= diff;
00080
00081
00082
00083 if(residual_rot <= 0)
00084 {
00085 end_angle = current_rot_norm;
00086 end_stamp = stamp;
00087 started_ = false;
00088 ROS_INFO("Finished snapshot at %f degree!", current_rot_norm * 180.0 / M_PI);
00089 return true;
00090 }
00091 previous_rot = current_rot_norm;
00092 return false;
00093 }
00094
00095 void RotunitSnapshotter::makeSnapshot(const uos_rotunit_snapshotter::RotunitSnapshotGoalConstPtr &goal){
00096 finished_ = false;
00097 if(!continuous)
00098 state_sub_ = nh_.subscribe("joint_states", 1000, &RotunitSnapshotter::rotCallback, this);
00099 boost::mutex::scoped_lock lock(mutex_);
00100 while (!finished_)
00101 condition_.wait(lock);
00102
00103 server_.setSucceeded(result_);
00104 }
00105
00106 void RotunitSnapshotter::rotCallback(const sensor_msgs::JointState::ConstPtr &jointState){
00107 boost::mutex::scoped_lock lock(mutex_);
00108
00109 if(server_.isPreemptRequested() || !ros::ok()){
00110 ROS_INFO("%s: Preempted", action_name_.c_str());
00111
00112 finished_ = true;
00113 server_.setPreempted();
00114 condition_.notify_one();
00115 return;
00116 }
00117 int index = getIndex(jointState);
00118 if(index == -1)
00119 return;
00120
00121 double rot = jointState->position[index];
00122 ROS_DEBUG("Current angle: %f", rot * 180 /M_PI);
00123
00124 if(checkIfFinished(rot, jointState->header.stamp)){
00125 laser_assembler::AssembleScans2 srv;
00126 srv.request.begin = begin_stamp;
00127 srv.request.end = end_stamp;
00128
00129 ROS_INFO("Call assembler with a duration of %fsec",
00130 end_stamp.toSec()-begin_stamp.toSec());
00131
00132 if (client_.call(srv)){
00133 cloud_pub_.publish(srv.response.cloud);
00134 ROS_INFO("Published scan with %d points", srv.response.cloud.height * srv.response.cloud.width);
00135 uos_rotunit_snapshotter::RotunitSnapshot snapshot;
00136 snapshot.header.stamp = end_stamp;
00137 snapshot.cloud = srv.response.cloud;
00138 snapshot.begin_angle = begin_angle;
00139 snapshot.end_angle = end_angle;
00140 snapshot.scan_time = end_stamp - begin_stamp;
00141 result_.snapshot = snapshot;
00142
00143 snapshot_pub_.publish(snapshot);
00144
00145 finished_ = true;
00146 if(!continuous)
00147 state_sub_.shutdown();
00148 condition_.notify_one();
00149 }
00150 else
00151 ROS_ERROR("Error making service call\n") ;
00152 }
00153 }
00154
00155 int main(int argc, char** argv){
00156
00157 ros::init(argc, argv, "RotunitSnapshotter");
00158 ros::NodeHandle nh;
00159
00160 ROS_INFO("Waiting for [assemble_scans2] to be advertised");
00161 ros::service::waitForService("assemble_scans2");
00162 ROS_INFO("Found [assemble_scans2]! Starting the snapshotter");
00163
00164 RotunitSnapshotter snapshotter(nh, std::string("rotunit_snapshotter"));
00165 ros::spin();
00166 return EXIT_SUCCESS;
00167 }