@@ -448,7 +448,7 @@ void VizPoseGraph::publishSlamResidueVisual( int n ) const
448448
449449void VizPoseGraph::publishCameraVisualMarker ( const Matrix4d& wTc, const string& ns, float r, float g, float b,
450450 float linewidth_multiplier, float camera_size_multiplier,
451- float offset_x, float offset_y, float offset_z )
451+ float offset_x, float offset_y, float offset_z ) const
452452{
453453 visualization_msgs::Marker marker2 ;
454454 RosMarkerUtils::init_camera_marker ( marker2, camera_size_multiplier );
@@ -463,7 +463,7 @@ void VizPoseGraph::publishCameraVisualMarker( const Matrix4d& wTc, const string&
463463 pub_pgraph.publish ( marker2 );
464464}
465465
466- void VizPoseGraph::publishXYZAxis ( const Matrix4d& wT_axis, const string ns, int id, float scale )
466+ void VizPoseGraph::publishXYZAxis ( const Matrix4d& wT_axis, const string ns, int id, float scale ) const
467467{
468468 visualization_msgs::Marker axis;
469469 RosMarkerUtils::init_line_marker ( axis );
@@ -495,13 +495,13 @@ void VizPoseGraph::publishXYZAxis( const Matrix4d& wT_axis, const string ns, int
495495
496496}
497497
498- void VizPoseGraph::publishThisVisualMarker ( const visualization_msgs::Marker& the_marker )
498+ void VizPoseGraph::publishThisVisualMarker ( const visualization_msgs::Marker& the_marker ) const
499499{
500500 pub_pgraph.publish ( the_marker );
501501}
502502
503503
504- void VizPoseGraph::publishImage ( const cv::Mat& im )
504+ void VizPoseGraph::publishImage ( const cv::Mat& im ) const
505505{
506506 sensor_msgs::ImagePtr msg = cv_bridge::CvImage ( std_msgs::Header (), " bgr8" , im ).toImageMsg ();
507507 pub_image.publish ( msg );
0 commit comments