29 #include <sensor_msgs/Image.h>    31 #include <sensor_msgs/PointCloud2.h>    32 #include <sensor_msgs/LaserScan.h>    33 #include <sensor_msgs/CameraInfo.h>    34 #include <sensor_msgs/NavSatFix.h>    35 #include <geometry_msgs/PoseWithCovarianceStamped.h>    36 #include <rosgraph_msgs/Clock.h>    38 #include <nav_msgs/Odometry.h>    42 #include <std_srvs/Empty.h>    44 #include <rtabmap_ros/SetGoal.h>    56 #include <sys/ioctl.h>    60         bool charAvailable = 
true;
    68                 term2.c_lflag &= ~ICANON;
    69                 term2.c_lflag &= ~ECHO;
    70                 term2.c_lflag &= ~ISIG;
    72                 term2.c_cc[VTIME] = 0;
    73                 tcsetattr(0, TCSANOW, &term2);
    85                         charAvailable = 
false;
    88                 tcsetattr(0, TCSANOW, &term);
    96 bool pauseCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&)
   124 int main(
int argc, 
char** argv)
   132         bool publishClock = 
false;
   133         for(
int i=1;i<argc;++i)
   135                 if(strcmp(argv[i], 
"--clock") == 0)
   144         std::string 
frameId = 
"base_link";
   145         std::string odomFrameId = 
"odom";
   146         std::string cameraFrameId = 
"camera_optical_link";
   147         std::string scanFrameId = 
"base_laser_link";
   149         std::string databasePath = 
"";
   150         bool publishTf = 
true;
   152         bool useDbStamps = 
true;
   154         pnh.
param(
"frame_id", frameId, frameId);
   155         pnh.
param(
"odom_frame_id", odomFrameId, odomFrameId);
   156         pnh.
param(
"camera_frame_id", cameraFrameId, cameraFrameId);
   157         pnh.
param(
"scan_frame_id", scanFrameId, scanFrameId);
   158         pnh.
param(
"rate", rate, rate); 
   159         pnh.
param(
"database", databasePath, databasePath);
   160         pnh.
param(
"publish_tf", publishTf, publishTf);
   161         pnh.
param(
"start_id", startId, startId);
   164         double scanAngleMin, scanAngleMax, scanAngleIncrement, scanRangeMin, scanRangeMax;
   165         pnh.
param<
double>(
"scan_angle_min", scanAngleMin, -
M_PI);
   166         pnh.
param<
double>(
"scan_angle_max", scanAngleMax, 
M_PI);
   167         pnh.
param<
double>(
"scan_angle_increment", scanAngleIncrement, 
M_PI / 720.0);
   168         pnh.
param<
double>(
"scan_range_min", scanRangeMin, 0.0);
   169         pnh.
param<
double>(
"scan_range_max", scanRangeMax, 60);
   171         ROS_INFO(
"frame_id = %s", frameId.c_str());
   172         ROS_INFO(
"odom_frame_id = %s", odomFrameId.c_str());
   173         ROS_INFO(
"camera_frame_id = %s", cameraFrameId.c_str());
   174         ROS_INFO(
"scan_frame_id = %s", scanFrameId.c_str());
   176         ROS_INFO(
"publish_tf = %s", publishTf?
"true":
"false");
   177         ROS_INFO(
"start_id = %d", startId);
   178         ROS_INFO(
"Publish clock (--clock): %s", publishClock?
"true":
"false");
   180         if(databasePath.empty())
   182                 ROS_ERROR(
"Parameter \"database\" must be set (path to a RTAB-Map database).");
   186         if(databasePath.size() && databasePath.at(0) != 
'/')
   190         ROS_INFO(
"database = %s", databasePath.c_str());
   195                 ROS_ERROR(
"Cannot open database \"%s\".", databasePath.c_str());
   222                 clockPub = nh.
advertise<rosgraph_msgs::Clock>(
"/clock", 1);
   231         double acquisitionTime = timer.ticks();
   234                 ROS_INFO(
"Reading sensor data %d...", odom.
data().
id());
   240                         rosgraph_msgs::Clock msg;
   245                 sensor_msgs::CameraInfo camInfoA; 
   246                 sensor_msgs::CameraInfo camInfoB; 
   248                 camInfoA.K.assign(0);
   249                 camInfoA.K[0] = camInfoA.K[4] = camInfoA.K[8] = 1;
   250                 camInfoA.R.assign(0);
   251                 camInfoA.R[0] = camInfoA.R[4] = camInfoA.R[8] = 1;
   252                 camInfoA.P.assign(0);
   255                 camInfoA.header.frame_id = cameraFrameId;
   256                 camInfoA.header.stamp = time;
   265                                 ROS_WARN(
"Multi-cameras detected in database but this node cannot send multi-images yet...");
   272                                         camInfoA.D.resize(5,0);
   289                                 if(depthPub.
getTopic().empty()) depthPub = it.
advertise(
"depth_registered/image", 1);
   290                                 if(rgbCamInfoPub.
getTopic().empty()) rgbCamInfoPub = nh.
advertise<sensor_msgs::CameraInfo>(
"rgb/camera_info", 1);
   291                                 if(depthCamInfoPub.
getTopic().empty()) depthCamInfoPub = nh.
advertise<sensor_msgs::CameraInfo>(
"depth_registered/camera_info", 1);
   298                                 ROS_WARN(
"Multi-cameras detected in database but this node cannot send multi-images yet...");
   305                                         camInfoA.D.resize(8,0);
   324                                 if(leftCamInfoPub.
getTopic().empty()) leftCamInfoPub = nh.
advertise<sensor_msgs::CameraInfo>(
"left/camera_info", 1);
   325                                 if(rightCamInfoPub.
getTopic().empty()) rightCamInfoPub = nh.
advertise<sensor_msgs::CameraInfo>(
"right/camera_info", 1);
   343                                 scanPub = nh.
advertise<sensor_msgs::LaserScan>(
"scan", 1);
   346                                         ROS_INFO(
"Scan will be published.");
   350                                         ROS_INFO(
"Scan will be published with those parameters:");
   351                                         ROS_INFO(
"  scan_angle_min=%f", scanAngleMin);
   352                                         ROS_INFO(
"  scan_angle_max=%f", scanAngleMax);
   353                                         ROS_INFO(
"  scan_angle_increment=%f", scanAngleIncrement);
   354                                         ROS_INFO(
"  scan_range_min=%f", scanRangeMin);
   355                                         ROS_INFO(
"  scan_range_max=%f", scanRangeMax);
   358                         else if(scanCloudPub.
getTopic().empty())
   360                                 scanCloudPub = nh.
advertise<sensor_msgs::PointCloud2>(
"scan_cloud", 1);
   361                                 ROS_INFO(
"Scan cloud will be published.");
   369                         if(globalPosePub.
getTopic().empty())
   371                                 globalPosePub = nh.
advertise<geometry_msgs::PoseWithCovarianceStamped>(
"global_pose", 1);
   372                                 ROS_INFO(
"Global pose will be published.");
   380                                 gpsFixPub = nh.
advertise<sensor_msgs::NavSatFix>(
"gps/fix", 1);
   381                                 ROS_INFO(
"GPS will be published.");
   397                         if(!localTransform.
isNull())
   400                                 baseToCamera.child_frame_id = cameraFrameId;
   401                                 baseToCamera.header.frame_id = 
frameId;
   402                                 baseToCamera.header.stamp = time;
   410                                 odomToBase.child_frame_id = 
frameId;
   411                                 odomToBase.header.frame_id = odomFrameId;
   412                                 odomToBase.header.stamp = time;
   420                                 baseToLaserScan.child_frame_id = scanFrameId;
   421                                 baseToLaserScan.header.frame_id = 
frameId;
   422                                 baseToLaserScan.header.stamp = time;
   434                                 odomMsg.child_frame_id = 
frameId;
   435                                 odomMsg.header.frame_id = odomFrameId;
   436                                 odomMsg.header.stamp = time;
   438                                 UASSERT(odomMsg.pose.covariance.size() == 36 &&
   441                                 memcpy(odomMsg.pose.covariance.begin(), odom.
covariance().data, 36*
sizeof(double));
   452                         geometry_msgs::PoseWithCovarianceStamped msg;
   456                         msg.header.stamp = time;
   462                         sensor_msgs::NavSatFix msg;
   466                         msg.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
   467                         msg.position_covariance.at(0) = msg.position_covariance.at(4) = msg.position_covariance.at(8)= odom.
data().
gps().
error()* odom.
data().
gps().
error();
   477                                 rgbCamInfoPub.
publish(camInfoA);
   481                                 leftCamInfoPub.
publish(camInfoA);
   485                                 depthCamInfoPub.
publish(camInfoB);
   489                                 rightCamInfoPub.
publish(camInfoB);
   505                         sensor_msgs::ImagePtr imageRosMsg = img.
toImageMsg();
   506                         imageRosMsg->header.frame_id = cameraFrameId;
   507                         imageRosMsg->header.stamp = time;
   520                                 leftCamInfoPub.
publish(camInfoA);
   536                         sensor_msgs::ImagePtr imageRosMsg = img.
toImageMsg();
   537                         imageRosMsg->header.frame_id = cameraFrameId;
   538                         imageRosMsg->header.stamp = time;
   541                         depthCamInfoPub.
publish(camInfoB);
   549                         sensor_msgs::ImagePtr imageRosMsg = img.
toImageMsg();
   550                         imageRosMsg->header.frame_id = cameraFrameId;
   551                         imageRosMsg->header.stamp = time;
   554                         rightCamInfoPub.
publish(camInfoB);
   562                                 sensor_msgs::LaserScan msg;
   563                                 msg.header.frame_id = scanFrameId;
   564                                 msg.header.stamp = time;
   566                                 msg.angle_min = scanAngleMin;
   567                                 msg.angle_max = scanAngleMax;
   568                                 msg.angle_increment = scanAngleIncrement;
   569                                 msg.time_increment = 0.0;
   571                                 msg.range_min = scanRangeMin;
   572                                 msg.range_max = scanRangeMax;
   582                                 uint32_t rangesSize = 
std::ceil((msg.angle_max - msg.angle_min) / msg.angle_increment);
   583                                 msg.ranges.assign(rangesSize, 0.0);
   586                                 for (
int i=0; i<scan.cols; ++i)
   588                                         const float * ptr = scan.ptr<
float>(0,i);
   589                                         double range = 
hypot(ptr[0], ptr[1]);
   590                                         if (range >= msg.range_min && range <=msg.range_max)
   593                                                 if (angle >= msg.angle_min && angle <= msg.angle_max)
   595                                                         int index = (angle - msg.angle_min) / msg.angle_increment;
   596                                                         if (index>=0 && index<rangesSize && (range < msg.ranges[index] || msg.ranges[index]==0))
   598                                                                 msg.ranges[index] = range;
   608                                 sensor_msgs::PointCloud2 msg;
   610                                 msg.header.frame_id = scanFrameId;
   611                                 msg.header.stamp = time;
   625                                 std::list<std::string> strs = 
uSplit(goalStr, 
':');
   628                                         int goalId = atoi(strs.rbegin()->c_str());
   632                                                 ROS_WARN(
"Goal %d detected, calling rtabmap's set_goal service!", goalId);
   633                                                 rtabmap_ros::SetGoal setGoalSrv;
   634                                                 setGoalSrv.request.node_id = goalId;
   635                                                 setGoalSrv.request.node_label = 
"";
   638                                                         ROS_ERROR(
"Can't call \"set_goal\" service");
   658                                         ROS_INFO(
"resumed!");
   674                 data = reader.takeImage(&cameraInfo);
   677                 acquisitionTime = timer.ticks();
 static std::string homeDir()
const double & error() const
const double & stamp() const
const Transform & globalPose() const
const cv::Mat & covariance() const
const LaserScan & laserScanCompressed() const
std::string uReplaceChar(const std::string &str, char before, char after)
uint32_t getNumSubscribers() const
int main(int argc, char **argv)
bool call(const std::string &service_name, MReq &req, MRes &res)
const cv::Mat & depthOrRightRaw() const
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
pcl::PCLPointCloud2::Ptr RTABMAP_EXP laserScanToPointCloud2(const LaserScan &laserScan, const Transform &transform=Transform())
bool resumeCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
const std::vector< StereoCameraModel > & stereoCameraModels() const
const cv::Mat & data() const
INLINE Rall1d< T, V, S > hypot(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const cv::Mat & globalPoseCovariance() const
#define UASSERT(condition)
std::list< std::string > uSplit(const std::string &str, char separator=' ')
const double & altitude() const
bool pauseCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
static std::string currentDir(bool trailingSeparator=false)
sensor_msgs::ImagePtr toImageMsg() const
const std::vector< CameraModel > & cameraModels() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
const cv::Mat & imageRaw() const
const std::string TYPE_32FC1
const std::string TYPE_16UC1
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
GLM_FUNC_QUALIFIER T atan2(T x, T y)
void publish(const sensor_msgs::Image &message) const
void transformToPoseMsg(const rtabmap::Transform &transform, geometry_msgs::Pose &msg)
void uSleep(unsigned int ms)
std::string getTopic() const
const LaserScan & laserScanRaw() const
const cv::Mat & userDataRaw() const
const double & longitude() const
const double & latitude() const
image_transport::Publisher imagePub
float angleIncrement() const
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spinOnce()
const Transform & pose() const
GLM_FUNC_DECL genType ceil(genType const &x)
Transform localTransform() const
std::string getTopic() const