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
00035 #include <cstdio>
00036 #include <laser_joint_processor/joint_imager.h>
00037
00038 using namespace laser_joint_processor;
00039 using namespace std;
00040
00041 JointImager::JointImager()
00042 {
00043
00044
00045
00046 }
00047
00048 JointImager::~JointImager()
00049 {
00050
00051 for (unsigned int i=0; i<images.size(); i++)
00052 cvReleaseImage(&images[i]);
00053 }
00054
00055 bool JointImager::update(const calibration_msgs::DenseLaserSnapshot& snapshot,
00056 const settlerlib::SortedDeque<joint_states_settler::DeflatedJointStates>& cache,
00057 const ros::Duration& max_interp)
00058 {
00059 if (cache.size() == 0)
00060 return false;
00061
00062 unsigned int num_channels = cache.back().channels_.size();
00063
00064
00065 allocateImages(snapshot.num_scans, snapshot.readings_per_scan, num_channels);
00066
00067 vector<double> cur_positions;
00068
00069
00070
00071 unsigned int after_index = 0;
00072 for (unsigned int i=0; i<snapshot.num_scans; i++)
00073 {
00074 for (unsigned int j=0; j<snapshot.readings_per_scan; j++)
00075 {
00076 ros::Time pixel_time = snapshot.scan_start[i] + ros::Duration(snapshot.time_increment * j);
00077 while(after_index < cache.size() && cache[after_index].header.stamp < pixel_time)
00078 after_index++;
00079 assert(after_index < cache.size());
00080 assert(after_index > 0);
00081
00082
00083 ros::Duration interp_diff = cache[after_index].header.stamp - cache[after_index-1].header.stamp;
00084 if (interp_diff > max_interp)
00085 {
00086 ROS_WARN("Interpolating between elems that are [%.2fs] apart. Probably dopped some messages. Going to ignore this snapshot", interp_diff.toSec());
00087 return false;
00088 }
00089
00090 settlerlib::Deflated::interp(cache[after_index-1], cache[after_index], pixel_time, cur_positions);
00091
00092
00093 for (unsigned int k=0;k<num_channels;k++)
00094 *(((float*)(images[k]->imageData + images[k]->widthStep*i))+2*j + 0) = cur_positions[k];
00095 }
00096 ros::Time scan_start_time = snapshot.scan_start[i];
00097 ros::Time scan_end_time = snapshot.scan_start[i] + ros::Duration(snapshot.time_increment * (snapshot.readings_per_scan-1));
00098
00099 for (unsigned int k=0; k<num_channels; k++)
00100 {
00101 float start_pos = *(((float*)(images[k]->imageData + images[k]->widthStep*i))+2*0 + 0);
00102 float end_pos = *(((float*)(images[k]->imageData + images[k]->widthStep*i))+2*(snapshot.readings_per_scan-1) + 0);
00103 float vel = (end_pos - start_pos) / (scan_end_time-scan_start_time).toSec();
00104
00105 float* vel_ptr = (float*)(images[k]->imageData + images[k]->widthStep*i) + 2*0 + 1;
00106 for (unsigned int j=0; j<snapshot.readings_per_scan; j++)
00107 {
00108 *vel_ptr = vel;
00109 vel_ptr += 2;
00110 }
00111 }
00112 }
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146 return true;
00147 }
00148
00149 void JointImager::displayImage(unsigned int i)
00150 {
00151 IplImage* image = getJointImage(i);
00152
00153 for (int i=0; i<image->height; i++)
00154 {
00155 for (int j=0; j<image->width; j++)
00156 {
00157 printf("%5.2f ", *((float*)(image->imageData + i*image->widthStep) + j*image->nChannels));
00158 }
00159 printf("\n");
00160 }
00161 }
00162
00163 void JointImager::writeImage(unsigned int i, const string& filename)
00164 {
00165 FILE* file = fopen(filename.c_str(), "w");
00166
00167 if (file)
00168 printf("About to write to file %s\n", filename.c_str());
00169
00170 IplImage* image = getJointImage(i);
00171
00172 for (int i=0; i<image->height; i++)
00173 {
00174 for (int j=0; j<image->width; j++)
00175 {
00176 fprintf(file, "% 3.2f ", *((float*)(image->imageData + i*image->widthStep) + j*image->nChannels));
00177 }
00178 fprintf(file, "\n");
00179 }
00180
00181 fclose(file);
00182 }
00183
00184
00185 bool JointImager::interpPosition(const ros::Time& target,
00186 const settlerlib::SortedDeque<joint_states_settler::DeflatedJointStates>& cache,
00187 vector<double>& result)
00188 {
00189 bool success;
00190 joint_states_settler::DeflatedJointStates before;
00191 joint_states_settler::DeflatedJointStates after;
00192
00193 success = cache.getElemBeforeTime(target, before);
00194 if (!success)
00195 {
00196 ROS_ERROR("Couldn't find elem before time");
00197 return false;
00198 }
00199 success = cache.getElemAfterTime(target, after);
00200 if (!success)
00201 {
00202 ROS_ERROR("Couldn't find elem after time");
00203 return false;
00204 }
00205 if (before.channels_.size() != after.channels_.size())
00206 {
00207 ROS_ERROR("# of joints has changed in the middle of a run");
00208 return false;
00209 }
00210
00211 success = settlerlib::Deflated::interp(before, after, target, result);
00212 if (!success)
00213 {
00214 ROS_ERROR("Error performing interpolation");
00215 return false;
00216 }
00217
00218 return true;
00219 }
00220
00221 bool JointImager::computeVelocity(const ros::Time& start, const ros::Time& end,
00222 const settlerlib::SortedDeque<joint_states_settler::DeflatedJointStates>& cache,
00223 vector<double>& result)
00224 {
00225 vector<double> start_positions;
00226 vector<double> end_positions;
00227
00228 bool success;
00229 success = interpPosition(start, cache, start_positions);
00230 if (!success)
00231 {
00232 ROS_ERROR("Error extracting start position");
00233 return false;
00234 }
00235
00236 success = interpPosition(end, cache, end_positions);
00237 if (!success)
00238 {
00239 ROS_ERROR("Error extracting start position");
00240 return false;
00241 }
00242
00243 if (start_positions.size() != end_positions.size())
00244 {
00245 ROS_ERROR("# of joints has changed during run. Can't compute velocity between samples");
00246 return false;
00247 }
00248
00249 const unsigned int N = start_positions.size();
00250
00251 result.resize(N);
00252 for (unsigned int i=0; i<N; i++)
00253 result[i] = (end_positions[i] - start_positions[i]) / (end-start).toSec();
00254
00255 return true;
00256 }
00257
00258 void JointImager::allocateImages(unsigned int height, unsigned int width, unsigned int channels)
00259 {
00260
00261 for (unsigned int i=0; i<images.size(); i++)
00262 cvReleaseImage(&images[i]);
00263
00264 images.resize(channels);
00265
00266 CvSize image_size = cvSize(width, height);
00267
00268 for (unsigned int i=0; i<channels; i++)
00269 images[i] = cvCreateImage(image_size, IPL_DEPTH_32F, 2);
00270 }
00271
00272 IplImage* JointImager::getJointImage(unsigned int index) const
00273 {
00274 return images[index];
00275 }