39 #include <multisense_ros/DeviceInfo.h>    40 #include <multisense_ros/RawCamConfig.h>    41 #include <multisense_ros/RawCamCal.h>    42 #include <multisense_ros/RawCamData.h>    43 #include <multisense_ros/RawLidarData.h>    44 #include <multisense_ros/RawLidarCal.h>    45 #include <multisense_lib/MultiSenseTypes.hh>    49 #include <dynamic_reconfigure/DoubleParameter.h>    50 #include <dynamic_reconfigure/StrParameter.h>    51 #include <dynamic_reconfigure/Reconfigure.h>    52 #include <dynamic_reconfigure/Config.h>    56 #define TOPIC_DEVICE_INFO     "/multisense/calibration/device_info"    57 #define TOPIC_RAW_CAM_CAL     "/multisense/calibration/raw_cam_cal"    58 #define TOPIC_RAW_CAM_CONFIG  "/multisense/calibration/raw_cam_config"    59 #define TOPIC_RAW_CAM_DATA    "/multisense/calibration/raw_cam_data"    60 #define TOPIC_RAW_LIDAR       "/multisense/calibration/raw_lidar_data"    61 #define TOPIC_RAW_LIDAR_CAL   "/multisense/calibration/raw_lidar_cal"    69     LaserHelper() : motion_started_(
false) {}
    71     void callback(
const multisense_ros::RawLidarData::ConstPtr& 
msg)
    77         if (motion_started_ || 0 == scans_.size())
    78             scans_.push_back(msg);
    80         if (!motion_started_) {
    81             std::list<multisense_ros::RawLidarData::ConstPtr>::const_iterator it = scans_.begin();
    83             if (msg->angle_start != (*it)->angle_start) {
    84                 motion_started_ = 
true;
    86                 scans_.push_back(msg);
    97         std::list<multisense_ros::RawLidarData::ConstPtr>::const_iterator it;
   103         if (scans_.end() == it)
   109         double previous_start = (*it)->angle_start / 1000000.0;
   110         double total_swept    = 0.0;
   112         for (it = scans_.begin(); it != scans_.end(); it++) {
   114             double current_start = (*it)->angle_start / 1000000.0;
   115             double current_swept = current_start - previous_start;
   120             while(current_swept > M_PI)
   121                 current_swept -= 2*M_PI;
   122             while(current_swept < -M_PI)
   123                 current_swept += 2*M_PI;
   128             total_swept += current_swept;
   133             previous_start = current_start;
   136         return ( fabs(total_swept) > 2.0 * M_PI);
   144     bool getRotation(std::list<multisense_ros::RawLidarData::ConstPtr>& scan_collection)
   151                                             std::bind(&LaserHelper::callback, 
this, std::placeholders::_1));
   163                 scan_collection = scans_;
   174 #if __cplusplus >= 201103   175     static constexpr 
double SCAN_COLLECT_TIMEOUT = 20.0; 
   177     static const double SCAN_COLLECT_TIMEOUT = 20.0; 
   180     bool motion_started_;
   182     std::list<multisense_ros::RawLidarData::ConstPtr> scans_;
   185 void setConf(
const dynamic_reconfigure::Config& conf)
   187     dynamic_reconfigure::ReconfigureRequest  srv_req;
   188     dynamic_reconfigure::ReconfigureResponse srv_resp;
   190     srv_req.config = conf;
   195 void setMotorSpeed(
double radPerSec)
   197     dynamic_reconfigure::DoubleParameter double_param;
   198     dynamic_reconfigure::Config          conf;
   200     double_param.name  = 
"motor_speed";
   201     double_param.value = radPerSec;
   202     conf.doubles.push_back(double_param);
   207 void setResolution(
const std::string& res)
   209     dynamic_reconfigure::StrParameter str_param;
   210     dynamic_reconfigure::Config       conf;
   212     str_param.name  = 
"resolution";
   213     str_param.value = res;
   214     conf.strs.push_back(str_param);
   228         std::string(argvPP[1]) == 
"--help" ||
   229         std::string(argvPP[1]) == 
"-h") {
   231         printf(
"Usage: %s <out_bag_filename>\n", argvPP[0]);
   235     std::string outfile(argvPP[1]);
   237     printf(
"Capturing device information... "); fflush(stdout);
   238     multisense_ros::DeviceInfo::ConstPtr device_info = ros::topic::waitForMessage<multisense_ros::DeviceInfo>(
TOPIC_DEVICE_INFO, nh);
   240         printf(
"  Error capturing DeviceInfo. Exiting\n");
   243     printf(
"  Success\n");
   245     switch(device_info->imagerType) {
   248       printf(
"Imager type is CMV2000; setting resolution to 1024x544x128... ");
   249       setResolution(
"1024x544x128");
   253       printf(
"Imager type is CMV4000; setting resolution to 1024x1024x128... ");
   254       setResolution(
"1024x1024x128");
   257       printf(
"Imager type is not recognized; not setting resolution... ");
   258       printf(
"  Error setting imager resolution.  Exiting\n");
   264     printf(
"Capturing lidar calibration... ");
   265     multisense_ros::RawLidarCal::ConstPtr lidar_cal = ros::topic::waitForMessage<multisense_ros::RawLidarCal>(
TOPIC_RAW_LIDAR_CAL, nh);
   267         printf(
"  Error capturing RawLidarCal. Exiting\n");
   270     printf(
"  Success\n");
   272     printf(
"Capturing camera calibration... "); fflush(stdout);
   273     multisense_ros::RawCamCal::ConstPtr cam_cal = ros::topic::waitForMessage<multisense_ros::RawCamCal>(
TOPIC_RAW_CAM_CAL, nh);
   275         printf(
"  Error capturing RawCamCal. Exiting\n");
   278     printf(
"  Success\n");
   280     printf(
"Capturing camera config... "); fflush(stdout);
   281     multisense_ros::RawCamConfig::ConstPtr cam_config = ros::topic::waitForMessage<multisense_ros::RawCamConfig>(
TOPIC_RAW_CAM_CONFIG, nh);
   283         printf(
"  Error capturing RawCamConfig. Exiting\n");
   286     printf(
"  Success\n");
   288     printf(
"Capturing a single left-rectified/disparity image pair... "); fflush(stdout);
   289     multisense_ros::RawCamData::ConstPtr cam_data = ros::topic::waitForMessage<multisense_ros::RawCamData>(
TOPIC_RAW_CAM_DATA, nh);
   291         printf(
"  Error capturing RawCamData. Exiting\n");
   294     printf(
"  Success\n");
   296     printf(
"Capturing a full rotation of lidar scans... "); fflush(stdout);
   298     setMotorSpeed(0.785);
   300     LaserHelper laser_helper;
   301     std::list<multisense_ros::RawLidarData::ConstPtr> raw_lidar_data;
   303     if (
false == laser_helper.getRotation(raw_lidar_data)) {
   304         printf(
"  Error capturing RawLidarData...\n");
   307     printf(
"  Captured %zu lidar scans\n", raw_lidar_data.size());
   314     printf(
"Saving data to file [%s]\n", outfile.c_str());
   324     std::list<multisense_ros::RawLidarData::ConstPtr>::const_iterator it;
   325     for (it = raw_lidar_data.begin(); it != raw_lidar_data.end(); it++)
   329     printf(
"  Success\n");
 
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_COLOR
void open(std::string const &filename, uint32_t mode=bagmode::Read)
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_GREY
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
#define TOPIC_DEVICE_INFO
const Time TIME_MIN(0, 1)
bool call(const std::string &service_name, MReq &req, MRes &res)
int main(int argc, char **argvPP)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define TOPIC_RAW_CAM_DATA
#define TOPIC_RAW_LIDAR_CAL
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV4000_GREY
void setCallbackQueue(CallbackQueueInterface *queue)
#define TOPIC_RAW_CAM_CAL
#define TOPIC_RAW_CAM_CONFIG
static CRL_CONSTEXPR uint32_t IMAGER_TYPE_CMV2000_COLOR