Skip to content

Commit 45f3e02

Browse files
committedJun 29, 2015
fixed build bor rtabmap 0.10.1
1 parent b98f34d commit 45f3e02

File tree

6 files changed

+21
-11
lines changed

6 files changed

+21
-11
lines changed
 

‎CMakeLists.txt

+1-2
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ find_package(octomap_ros)
1717

1818
## System dependencies are found with CMake's conventions
1919
# find_package(Boost REQUIRED COMPONENTS system)
20-
find_package(RTABMap 0.10.0 REQUIRED)
20+
find_package(RTABMap 0.10.1 REQUIRED)
2121

2222
find_package(OpenCV REQUIRED)
2323

@@ -49,7 +49,6 @@ add_message_files(
4949
NodeData.msg
5050
Link.msg
5151
OdomInfo.msg
52-
UserData.msg
5352
Point2f.msg
5453
)
5554

‎cfg/Camera.cfg

-2
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,6 @@ gen = ParameterGenerator()
77

88
gen.add("device_id", int_t, 0, "Camera device ID", 0, 0, 7)
99
gen.add("frame_rate", double_t, 0, "Frame rate", 15.0, 0.0, 100.0)
10-
gen.add("width", int_t, 0, "Width", 640, 0, 1920)
11-
gen.add("height", int_t, 0, "Image height", 480, 0, 1080)
1210
gen.add("video_or_images_path", str_t, 0, "Video or images directory path", "")
1311
gen.add("pause", bool_t, 0, "Pause", False)
1412

‎msg/NodeData.msg

+4-1
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@ int32 mapId
44
int32 weight
55
float64 stamp
66
string label
7-
UserData userData
87

98
# Pose from odometry not corrected
109
geometry_msgs/Pose pose
@@ -31,6 +30,10 @@ geometry_msgs/Transform[] localTransform
3130
uint8[] laserScan
3231
int32 laserScanMaxPts
3332

33+
# compressed user data
34+
# use rtabmap::util3d::uncompressData() from "rtabmap/core/util3d.h"
35+
uint8[] userData
36+
3437
# std::multimap<wordId, cv::Keypoint>
3538
# std::multimap<wordId, pcl::PointXYZ>
3639
int32[] wordIds

‎msg/UserData.msg

-2
This file was deleted.

‎src/CoreWrapper.cpp

+7
Original file line numberDiff line numberDiff line change
@@ -258,6 +258,7 @@ CoreWrapper::CoreWrapper(bool deleteDbOnStart) :
258258
oldParameterNames.push_back("RGBD/LocalLoopDetectionRadius");
259259
oldParameterNames.push_back("RGBD/ToroIterations");
260260
oldParameterNames.push_back("Mem/RehearsedNodesKept");
261+
oldParameterNames.push_back("Odom/PnPEstimation");
261262
for(std::list<std::string>::iterator iter=oldParameterNames.begin(); iter!=oldParameterNames.end(); ++iter)
262263
{
263264
std::string vStr;
@@ -309,6 +310,12 @@ CoreWrapper::CoreWrapper(bool deleteDbOnStart) :
309310
{
310311
ROS_WARN("Parameter \"RGBD/PlanVirtualLinksMaxDiffID\" doesn't exist anymore.");
311312
}
313+
else if(iter->compare("RGBD/LocalLoopDetectionMaxDiffID") == 0)
314+
{
315+
ROS_WARN("Parameter name changed: Odom/PnPEstimation -> %s. Please update your launch file accordingly.",
316+
Parameters::kOdomEstimationType().c_str());
317+
parameters_.at(Parameters::kOdomEstimationType())= uNumber2Str(1);
318+
}
312319
}
313320
}
314321

‎src/MsgConversion.cpp

+9-4
Original file line numberDiff line numberDiff line change
@@ -452,20 +452,25 @@ rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData & msg)
452452
msg.stamp,
453453
msg.label,
454454
transformFromPoseMsg(msg.pose),
455-
msg.userData.data,
456455
stereoModel.isValid()?
457456
rtabmap::SensorData(
458457
compressedMatFromBytes(msg.laserScan),
459458
msg.laserScanMaxPts,
460459
compressedMatFromBytes(msg.image),
461460
compressedMatFromBytes(msg.depth),
462-
stereoModel):
461+
stereoModel,
462+
msg.id,
463+
msg.stamp,
464+
compressedMatFromBytes(msg.userData)):
463465
rtabmap::SensorData(
464466
compressedMatFromBytes(msg.laserScan),
465467
msg.laserScanMaxPts,
466468
compressedMatFromBytes(msg.image),
467469
compressedMatFromBytes(msg.depth),
468-
models));
470+
models,
471+
msg.id,
472+
msg.stamp,
473+
compressedMatFromBytes(msg.userData)));
469474
s.setWords(words);
470475
s.setWords3(words3D);
471476
return s;
@@ -478,11 +483,11 @@ void nodeDataToROS(const rtabmap::Signature & signature, rtabmap_ros::NodeData &
478483
msg.weight = signature.getWeight();
479484
msg.stamp = signature.getStamp();
480485
msg.label = signature.getLabel();
481-
msg.userData.data = signature.getUserData();
482486
transformToPoseMsg(signature.getPose(), msg.pose);
483487
compressedMatToBytes(signature.sensorData().imageCompressed(), msg.image);
484488
compressedMatToBytes(signature.sensorData().depthOrRightCompressed(), msg.depth);
485489
compressedMatToBytes(signature.sensorData().laserScanCompressed(), msg.laserScan);
490+
compressedMatToBytes(signature.sensorData().userDataCompressed(), msg.userData);
486491
msg.baseline = 0;
487492
if(signature.sensorData().cameraModels().size())
488493
{

0 commit comments

Comments
 (0)
Please sign in to comment.