Skip to content

Commit 2f91e2f

Browse files
authored
Merge pull request #3 from mpkuse/dev-wTimu-100hz
Dev w timu 100hz
2 parents 8bf7000 + 2982a24 commit 2f91e2f

7 files changed

Lines changed: 294 additions & 65 deletions

File tree

src/Composer.cpp

Lines changed: 122 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -227,10 +227,23 @@ void Composer::pose_assember_thread( int looprate )
227227
}
228228

229229

230+
int Composer::get_last_known_camerapose( Matrix4d& w_T_lastcam, ros::Time& stamp_of_it )
231+
{
232+
std::lock_guard<std::mutex> lk(mx);
233+
const int sz = global_lmb.size();
234+
if( sz == 0 )
235+
return -1;
236+
237+
auto it = global_lmb.rbegin();
238+
w_T_lastcam = *(it);
239+
240+
stamp_of_it = manager->getNodeTimestamp( sz-1 );
241+
return sz-1;
242+
}
230243

231244
// #define __Composer_bf_traj_publish_thread( msg ) msg;
232245
#define __Composer_bf_traj_publish_thread( msg ) ;
233-
void Composer::bf_traj_publish_thread( int looprate )
246+
void Composer::bf_traj_publish_thread( int looprate ) const
234247
{
235248
//--- Options
236249
const int options_line_color_style = 10; // should be either 10 or 12. 10:color by WorldID; 12: //color by world setID
@@ -242,6 +255,7 @@ void Composer::bf_traj_publish_thread( int looprate )
242255
cout << TermColor::GREEN() << "start `Composer::bf_traj_publish_thread` @ " << looprate << " hz" << TermColor::RESET() << endl;
243256
assert( looprate > 0 && looprate < 50 );
244257
ros::Rate rate(looprate);
258+
bool published_axis = false;
245259

246260
static thread_local std::mt19937 generator;
247261
std::uniform_int_distribution<int> distribution(0,100);
@@ -327,14 +341,20 @@ void Composer::bf_traj_publish_thread( int looprate )
327341

328342
}
329343

344+
if( published_axis==false || rand() % 100 == 0 ) {
345+
// Publish Axis - publish infrequently
346+
Matrix4d _axis_pose = Matrix4d::Identity();
347+
viz->publishXYZAxis( _axis_pose, "opt_traj_axis", 0 );
348+
published_axis = true;
349+
}
330350
}
331351

332352
cout << TermColor::RED() << "Finished `Composer::bf_traj_publish_thread`\n" << TermColor::RESET() << endl;
333353
}
334354

335355

336356

337-
void Composer::cam_visual_publish_thread( int looprate )
357+
void Composer::cam_visual_publish_thread( int looprate ) const
338358
{
339359
//--- Options
340360
const int options_linewidth_multiplier = 3; //default 3
@@ -381,7 +401,7 @@ void Composer::cam_visual_publish_thread( int looprate )
381401

382402
// #define __Composer__loopedge_publish_thread(msg) msg;
383403
#define __Composer__loopedge_publish_thread(msg) ;
384-
void Composer::loopedge_publish_thread( int looprate )
404+
void Composer::loopedge_publish_thread( int looprate ) const
385405
{
386406
cout << TermColor::GREEN() << "start `Composer::loopedge_publish_thread` @" << looprate << " hz" << TermColor::RESET() << endl;
387407
assert( looprate > 0 && looprate < 50 );
@@ -468,7 +488,7 @@ void Composer::loopedge_publish_thread( int looprate )
468488

469489
// #define __Composer__disjointset_statusimage_publish_thread(msg) msg;
470490
#define __Composer__disjointset_statusimage_publish_thread(msg) ;
471-
void Composer::disjointset_statusimage_publish_thread( int looprate )
491+
void Composer::disjointset_statusimage_publish_thread( int looprate ) const
472492
{
473493
cout << TermColor::GREEN() << "start `Composer::disjointset_statusimage_publish_thread` @" << looprate << " hz" << TermColor::RESET() << endl;
474494
assert( looprate > 0 && looprate < 50 );
@@ -509,3 +529,101 @@ void Composer::disjointset_statusimage_publish_thread( int looprate )
509529

510530
cout << TermColor::RED() << "Finished `Composer::disjointset_statusimage_publish_thread`\n" << TermColor::RESET() << endl;
511531
}
532+
533+
534+
535+
536+
//------ Publish body pose @200Hz ------//
537+
538+
void Composer::setup_200hz_publishers()
539+
{
540+
// pubx =
541+
// cmpr->set_200hz_marker_pub( pubx )
542+
string marker_topic = string( "hz200/visualization_marker");
543+
ROS_INFO( "[Composer::setup_200hz_publishers] Publish to %s", marker_topic.c_str() );
544+
pub_hz200_marker = nh.advertise<visualization_msgs::Marker>( marker_topic , 1000 );
545+
546+
547+
// puby =
548+
// cmpr->set_200hz_odom_pub( puby )
549+
}
550+
551+
552+
// #define _Composer__imu_propagate_callback_( msg ) msg;
553+
#define _Composer__imu_propagate_callback_( msg ) ;
554+
void Composer::imu_propagate_callback( const nav_msgs::Odometry::ConstPtr& msg )
555+
{
556+
_Composer__imu_propagate_callback_(
557+
cout << TermColor::iBLUE() << "[Composer::imu_propagate_callback] t=" << msg->header.stamp << TermColor::RESET() << endl;
558+
)
559+
560+
Matrix4d w_T_imucurr; // = pose from msg
561+
PoseManipUtils::geometry_msgs_Pose_to_eigenmat( msg->pose.pose, w_T_imucurr );
562+
563+
564+
565+
566+
//
567+
// Last Known camera-pose? - after pose graph solver
568+
Matrix4d wf_T_camlast;
569+
ros::Time cam_t;
570+
int posegraph_nodeidx = get_last_known_camerapose( wf_T_camlast, cam_t );
571+
if( posegraph_nodeidx < 0 ) {
572+
_Composer__imu_propagate_callback_(
573+
cout << TermColor::iYELLOW() << "posegraph_nodeidx was neg, meaning non existant last known cam pose\n" << TermColor::RESET();
574+
)
575+
return ;
576+
}
577+
578+
_Composer__imu_propagate_callback_(
579+
cout << "\tLast known camera-pose is at posegraphnode postion=" << posegraph_nodeidx << " is at t=" << cam_t << " which is "<< msg->header.stamp - cam_t << " behind current imu_prop msg\n";
580+
)
581+
582+
583+
//
584+
// extrinsic-calibration value: imu_T_cam
585+
if( manager->is_imu_T_cam_available() == false ) {
586+
_Composer__imu_propagate_callback_(
587+
cout << TermColor::iYELLOW() << "imu-cam extrinsic is not yet available\n" << TermColor::RESET() << endl;
588+
)
589+
return;
590+
}
591+
Matrix4d imu_T_cam = manager->get_imu_T_cam();
592+
593+
//
594+
// relative pose between when imu at t=now_t and when imu was at t=last_known_t
595+
Matrix4d w_T_imulast = manager->getNodePose(posegraph_nodeidx) * imu_T_cam.inverse();
596+
Matrix4d imulast_T_imucurr = w_T_imulast.inverse() * w_T_imucurr;
597+
598+
599+
//
600+
// Add this relative pose to `wf_T_camlast`
601+
Matrix4d wf_T_imucurr = ( wf_T_camlast * imu_T_cam.inverse() ) * imulast_T_imucurr;
602+
603+
604+
605+
//
606+
// Make viz marker and publish
607+
visualization_msgs::Marker imu_m;
608+
RosMarkerUtils::init_XYZ_axis_marker( imu_m, 1.0 );
609+
imu_m.ns = "hz100_imu";
610+
imu_m.id = 0;
611+
RosMarkerUtils::setpose_to_marker( wf_T_imucurr, imu_m );
612+
pub_hz200_marker.publish( imu_m );
613+
614+
visualization_msgs::Marker imu_txt;
615+
RosMarkerUtils::init_text_marker( imu_txt );
616+
imu_txt.ns = "hz100_imu_txt";
617+
imu_txt.text = "IMU@200hz";
618+
imu_txt.scale.z = 0.5;
619+
RosMarkerUtils::setcolor_to_marker( 1.0, 1.0, 1.0, imu_txt );
620+
RosMarkerUtils::setpose_to_marker( wf_T_imucurr, imu_txt );
621+
pub_hz200_marker.publish( imu_txt );
622+
623+
624+
625+
626+
}
627+
628+
629+
//------ END Publish body pose @200Hz ------//

src/Composer.h

Lines changed: 30 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,9 @@
1414
#include <mutex>
1515
#include <atomic>
1616

17+
// ROS
18+
19+
1720
// Eigen
1821
#include <Eigen/Dense>
1922
#include <Eigen/Geometry>
@@ -29,12 +32,18 @@ using namespace std;
2932
class Composer
3033
{
3134
public:
32-
Composer( const NodeDataManager * manager, const PoseGraphSLAM * slam, const VizPoseGraph * viz )
33-
: manager(manager), slam(slam), viz(viz)
35+
Composer( const NodeDataManager * manager,
36+
const PoseGraphSLAM * slam,
37+
const VizPoseGraph * viz,
38+
ros::NodeHandle& _nh
39+
)
40+
: manager(manager), slam(slam), viz(viz), nh( _nh )
3441
{
3542
b_pose_assember = false;
3643
b_bf_traj_publish = false;
3744
b_cam_visual_publish = false;
45+
b_loopedge_publish = false;
46+
b_disjointset_statusimage_publish = false;
3847
}
3948

4049
private:
@@ -45,6 +54,7 @@ class Composer
4554
const NodeDataManager * manager;
4655
const PoseGraphSLAM * slam;
4756
const VizPoseGraph * viz ;
57+
ros::NodeHandle nh;
4858

4959

5060

@@ -58,6 +68,10 @@ class Composer
5868
void pose_assember_enable() { b_pose_assember = true;}
5969
void pose_assember_disable() {b_pose_assember = false; }
6070

71+
// Returns the last element in `global_lmb` along with the timestamp
72+
// Returns -1 when len(global_lmb) is zero, else return the posegraph node index of it.
73+
int get_last_known_camerapose( Matrix4d& w_T_lastcam, ros::Time& stamp_of_it );
74+
6175
private:
6276
atomic<bool> b_pose_assember;
6377
map<int, vector<Matrix4d> > global_jmb; // key: worldID, value: vector of poses
@@ -71,7 +85,7 @@ class Composer
7185
//-------------------------------------------//
7286
// makes use of global_jmb and publish all
7387
public:
74-
void bf_traj_publish_thread( int looprate=15 );
88+
void bf_traj_publish_thread( int looprate=15 ) const;
7589
void bf_traj_publish_enable() { b_bf_traj_publish = true;}
7690
void bf_traj_publish_disable() {b_bf_traj_publish = false; }
7791

@@ -86,7 +100,7 @@ class Composer
86100
//---------------------//
87101
// makes use of global_jmb and publish last cam
88102
public:
89-
void cam_visual_publish_thread( int looprate = 30 );
103+
void cam_visual_publish_thread( int looprate = 30 ) const;
90104
void cam_visual_publish_enable() { b_cam_visual_publish = true;}
91105
void cam_visual_publish_disable() {b_cam_visual_publish = false; }
92106

@@ -100,7 +114,7 @@ class Composer
100114
//-------------------------//
101115
// makes use of manager->getEdgeLen() and global_lmb and publish edges.
102116
public:
103-
void loopedge_publish_thread( int looprate = 10 );
117+
void loopedge_publish_thread( int looprate = 10 ) const;
104118
void loopedge_publish_enable() { b_loopedge_publish = true;}
105119
void loopedge_publish_disable() {b_loopedge_publish = false; }
106120

@@ -115,13 +129,23 @@ class Composer
115129
//--------------------------------//
116130
// makes use of manager->getEdgeLen() and global_lmb and publish edges.
117131
public:
118-
void disjointset_statusimage_publish_thread( int looprate = 10 );
132+
void disjointset_statusimage_publish_thread( int looprate = 10 ) const;
119133
void disjointset_statusimage_publish_enable() { b_disjointset_statusimage_publish = true;}
120134
void disjointset_statusimage_publish_disable() {b_disjointset_statusimage_publish = false; }
121135

122136
private:
123137
atomic<bool> b_disjointset_statusimage_publish;
124138

125139

140+
//-----------------------------------//
141+
//--- 200 Hz imu pose publication ---//
142+
//-----------------------------------//
143+
// Note: The publisher and subscribers are private to this thread itself.
144+
public:
145+
void setup_200hz_publishers();
146+
void imu_propagate_callback( const nav_msgs::Odometry::ConstPtr& msg );
147+
148+
private:
149+
ros::Publisher pub_hz200_marker;
126150

127151
};

0 commit comments

Comments
 (0)