Skip to content

Commit 8fa48c3

Browse files
committed
removed dependence on cerebro::LoopEdge, defined the incoming custom msg in this package. if you keep it the same as the cerebro, you can interoperate with cerebro
1 parent 3150326 commit 8fa48c3

7 files changed

Lines changed: 54 additions & 17 deletions

File tree

CMakeLists.txt

Lines changed: 17 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ find_package(catkin REQUIRED COMPONENTS
1414
image_transport
1515
cv_bridge
1616
#nap
17-
cerebro
17+
#cerebro
1818
nav_msgs
1919
)
2020

@@ -34,24 +34,35 @@ set( CMAKE_CXX_FLAGS "-fpermissive -std=c++11 -O3" )
3434

3535

3636

37+
38+
39+
40+
41+
add_message_files(
42+
FILES
43+
LoopEdge.msg
44+
)
45+
46+
3747
generate_messages(
3848
DEPENDENCIES
3949
std_msgs
4050
sensor_msgs
4151
geometry_msgs
4252
nav_msgs
4353
#nap
44-
cerebro
54+
#cerebro
4555
)
4656

4757

48-
4958
catkin_package(
5059
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime image_transport cv_bridge
5160
#nap
52-
cerebro
61+
#cerebro
5362
)
5463

64+
65+
5566
include_directories(
5667
${catkin_INCLUDE_DIRS}
5768
${CERES_INCLUDE_DIRS}
@@ -74,7 +85,8 @@ add_executable( keyframe_pose_graph_slam
7485

7586

7687
# this is needed to indicate this this executable depends on the messages of the pkg.
77-
add_dependencies(keyframe_pose_graph_slam cerebro_generate_messages_cpp)
88+
#add_dependencies(keyframe_pose_graph_slam cerebro_generate_messages_cpp)
89+
#add_dependencies(keyframe_pose_graph_slam )
7890

7991

8092
#add_executable( test_disjointset_imp src/test_disjointset.cpp )

msg/LoopEdge.msg

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
time timestamp0
2+
time timestamp1
3+
geometry_msgs/Pose pose_1T0 # pose of 0 as observed from 1.
4+
float32 weight
5+
string description

package.xml

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -44,20 +44,22 @@
4444
<build_depend>roscpp</build_depend>
4545
<build_depend>rospy</build_depend>
4646
<build_depend>std_msgs</build_depend>
47+
<build_depend>geometry_msgs</build_depend>
4748
<build_depend>message_generation</build_depend>
4849
<build_depend>image_transport</build_depend>
4950
<build_depend>cv_bridge</build_depend>
5051

51-
<build_depend>cerebro</build_depend>
52+
<!-- <build_depend>cerebro</build_depend> -->
5253

5354
<run_depend>roscpp</run_depend>
5455
<run_depend>rospy</run_depend>
5556
<run_depend>std_msgs</run_depend>
57+
<run_depend>geometry_msgs</run_depend>
5658
<run_depend>message_runtime</run_depend>
5759
<run_depend>image_transport</run_depend>
5860
<run_depend>cv_bridge</run_depend>
5961

60-
<run_depend>cerebro</run_depend>
62+
<!-- <run_depend>cerebro</run_depend> -->
6163

6264
<!-- The export tag contains other, unspecified, tags -->
6365
<export>

src/NodeDataManager.cpp

Lines changed: 11 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@ worlds_handle_raw_ptr = new Worlds();
1818

1919
}
2020

21+
// #define __NODEDATAMANAGER_CALLBACKS( msg ) msg;
22+
#define __NODEDATAMANAGER_CALLBACKS(msg) ;
2123
void NodeDataManager::camera_pose_callback( const nav_msgs::Odometry::ConstPtr& msg )
2224
{
2325
// ROS_INFO( "NodeDataManager::camera_pose_callback");
@@ -40,7 +42,9 @@ void NodeDataManager::camera_pose_callback( const nav_msgs::Odometry::ConstPtr&
4042
w_T_cam(1,3) = msg->pose.pose.position.y;
4143
w_T_cam(2,3) = msg->pose.pose.position.z;
4244
w_T_cam(3,3) = 1.0;
43-
// cout << "camera_pose_callback: " << node_pose.size() << " " << PoseManipUtils::prettyprintMatrix4d( w_T_cam ) << endl;
45+
__NODEDATAMANAGER_CALLBACKS(
46+
cout << "camera_pose_callback: node_pose.size()=" << node_pose.size() << " curr_pose=" << PoseManipUtils::prettyprintMatrix4d( w_T_cam ) << endl;
47+
)
4448

4549

4650
// co-variance
@@ -121,8 +125,11 @@ void NodeDataManager::camera_pose_callback( const nav_msgs::Odometry::ConstPtr&
121125
//
122126
//
123127
// }
124-
128+
#ifdef __USE_SELF_LOOPEDGE_MSG
129+
void NodeDataManager::loopclosure_pose_callback( const solve_keyframe_pose_graph::LoopEdge::ConstPtr& msg )
130+
#else
125131
void NodeDataManager::loopclosure_pose_callback( const cerebro::LoopEdge::ConstPtr& msg )
132+
#endif
126133
{
127134
// Add a new edge ( 2 node*)
128135

@@ -134,11 +141,11 @@ void NodeDataManager::loopclosure_pose_callback( const cerebro::LoopEdge::Const
134141
// assert( op_mode == 30 );
135142
string description = msg->description;
136143

137-
#if 0
144+
__NODEDATAMANAGER_CALLBACKS(
138145
cout << TermColor::iYELLOW() << "[NodeDataManager::loopclosure_pose_callback]";
139146
cout << "t_a=" << t_a << " t_b=" << t_b << " wt=" << msg->weight;
140147
cout << " description=" << msg->description << TermColor::RESET() << endl;
141-
#endif
148+
)
142149

143150

144151
// retrive rel-pose p_T_c

src/NodeDataManager.h

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,13 @@
3939
// ros messages
4040
#include <nav_msgs/Path.h>
4141
// #include <nap/NapMsg.h>
42+
#define __USE_SELF_LOOPEDGE_MSG
43+
44+
#ifdef __USE_SELF_LOOPEDGE_MSG
45+
#include <solve_keyframe_pose_graph/LoopEdge.h>
46+
#else
4247
#include <cerebro/LoopEdge.h>
48+
#endif
4349
#include <nav_msgs/Odometry.h>
4450
#include <visualization_msgs/Marker.h>
4551
#include <std_msgs/ColorRGBA.h>
@@ -75,7 +81,11 @@ class NodeDataManager
7581
// Callbacks core
7682
void camera_pose_callback( const nav_msgs::Odometry::ConstPtr& msg );
7783
// void loopclosure_pose_callback( const nap::NapMsg::ConstPtr& msg );
84+
#ifdef __USE_SELF_LOOPEDGE_MSG
85+
void loopclosure_pose_callback( const solve_keyframe_pose_graph::LoopEdge::ConstPtr& msg );
86+
#else
7887
void loopclosure_pose_callback( const cerebro::LoopEdge::ConstPtr& msg );
88+
#endif
7989

8090
void print_nodes_lengths() const;
8191

src/PoseGraphSLAM.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1103,8 +1103,8 @@ bool PoseGraphSLAM::saveAsJSON(const string base_path)
11031103

11041104
// This thread wakes up when there are new loopedges. This flag controls the printing on trigger.
11051105
// When debugging you want to keep the headers 'on'.
1106-
// #define ___trigger_header( msg ) msg;
1107-
#define ___trigger_header( msg ) ;
1106+
#define ___trigger_header( msg ) msg;
1107+
// #define ___trigger_header( msg ) ;
11081108

11091109
void PoseGraphSLAM::reinit_ceres_problem_onnewloopedge_optimize6DOF()
11101110
{

src/keyframe_pose_graph_slam_node.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1022,7 +1022,7 @@ void opt_traj_publisher_colored_by_world( const NodeDataManager * manager, const
10221022

10231023
}
10241024

1025-
cout << TermColor::BLUE() << "[opt_traj_publisher_colored_by_world] Took " << _time_jmb.toc_milli() << "ms to compute #nodes=" << manager->getNodeLen() << TermColor::RESET() << endl;
1025+
// cout << TermColor::BLUE() << "[opt_traj_publisher_colored_by_world] Took " << _time_jmb.toc_milli() << "ms to compute #nodes=" << manager->getNodeLen() << TermColor::RESET() << endl;
10261026
//-----------------------------------------------------------------------------------------------//
10271027
//------------------------- After this only uses jmb and lmb to publish -------------------------//
10281028
//-----------------------------------------------------------------------------------------------//
@@ -1236,7 +1236,7 @@ void opt_traj_publisher_colored_by_world( const NodeDataManager * manager, const
12361236

12371237
}
12381238

1239-
cout << TermColor::BLUE() << "[opt_traj_publisher_colored_by_world] Publish took " << _time_publih.toc_milli() << " ms" << endl;
1239+
// cout << TermColor::BLUE() << "[opt_traj_publisher_colored_by_world] Publish took " << _time_publih.toc_milli() << " ms" << endl;
12401240
// book keeping
12411241
// cerr << "\nSLEEP\n";
12421242
loop_rate.sleep();
@@ -1447,6 +1447,7 @@ int main( int argc, char ** argv)
14471447
// std::thread th_slam( &PoseGraphSLAM::new_optimize6DOF, slam );
14481448

14491449
slam->reinit_ceres_problem_onnewloopedge_optimize6DOF_enable();
1450+
slam->reinit_ceres_problem_onnewloopedge_optimize6DOF_disable();
14501451
std::thread th_slam( &PoseGraphSLAM::reinit_ceres_problem_onnewloopedge_optimize6DOF, slam );
14511452

14521453

@@ -1468,7 +1469,7 @@ int main( int argc, char ** argv)
14681469
options.line_color_style = 10;
14691470
options.linewidth_multiplier = 3; //0.25; //8
14701471
options.udumbe_offset_y = 30.0;
1471-
std::thread th6( opt_traj_publisher_colored_by_world, manager, slam, viz, options );
1472+
// std::thread th6( opt_traj_publisher_colored_by_world, manager, slam, viz, options );
14721473

14731474

14741475

@@ -1490,7 +1491,7 @@ int main( int argc, char ** argv)
14901491
// th3.join();
14911492
// th4.join();
14921493
th5.join();
1493-
th6.join();
1494+
// th6.join();
14941495

14951496
th_slam.join();
14961497

0 commit comments

Comments
 (0)