visualizer_ros.hpp 2.27 KB
Newer Older
1
2
3
4
#pragma once

#include "ros/node_handle.h"

5
#include "aicp_utils/visualizer.hpp"
6
7
8

#include <geometry_msgs/PoseStamped.h>
#include <nav_msgs/Path.h>
9

10
11
#include <eigen_conversions/eigen_msg.h>

12
#include <tf_conversions/tf_eigen.h>
13
14
15
#include <tf/transform_listener.h>
#include <tf/transform_broadcaster.h>

16
17
#include <Eigen/StdVector>

18
19
20
21
22
23
24
namespace aicp {

class ROSVisualizer : public Visualizer
{
public:

    ROSVisualizer(ros::NodeHandle& nh, std::string fixed_frame);
simalpha's avatar
simalpha committed
25
    ~ROSVisualizer(){}
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47

    // Publish cloud
    void publishCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
                      int param, // channel name
                      std::string name,
                      int64_t utime);
    void publishCloud(pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr& cloud,
                      int param, // channel name
                      std::string name,
                      int64_t utime);

    // Publish map
    void publishMap(pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
                    int64_t utime,
                    int channel); // 0 : /aicp/prior_map
                                  // 1 : /aicp/aligned_map

    // Publish octree
    void publishOctree(octomap::ColorOcTree*& octree,
                       std::string channel_name);

    // Publish corrected pose
simalpha's avatar
simalpha committed
48
49
    void publishPoses(Eigen::Isometry3d pose,
                      int param, std::string name, int64_t utime);
50
51
52
53

    // Publish tf from fixed_frame to odom
    void publishFixedFrameToOdomTF(Eigen::Isometry3d& fixed_frame_to_base_eigen, ros::Time msg_time);

simalpha's avatar
simalpha committed
54
    // Gets
55
    const std::vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d>>& getPath(){
simalpha's avatar
simalpha committed
56
57
58
        return path_;
    }

59
60
61
62
63
64
65
66
67
private:
    ros::NodeHandle& nh_;
    ros::Publisher cloud_pub_;
    ros::Publisher prior_map_pub_;
    ros::Publisher aligned_map_pub_;
    ros::Publisher pose_pub_;
    // Duplicates the list in collections renderer. assumed to be 3xN colors
    std::vector<double> colors_;
    // Path (vector of poses)
68
    std::vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d>> path_;
69
70
71
72
73
74
75
76
77
78

    std::string fixed_frame_; // map or map_test
    std::string odom_frame_;
    std::string base_frame_;

    // TF listener and broadcaster
    tf::TransformListener tf_listener_;
    tf::TransformBroadcaster tf_broadcaster_;
};
}