ros_publisher.cpp 5.53 KB
Newer Older
wangdawei's avatar
wangdawei committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
#include "ros_publisher.h"
namespace juefx{

RosPublisher::RosPublisher()
    : _msg_queue_size(100)
{

}

RosPublisher::~RosPublisher()
{

}

Publisher::Ptr RosPublisher::Instance()
{
    auto &publisher = Publisher::Instance();
    if(!publisher){
        publisher.reset(new RosPublisher());
    }
    return publisher;
}

void RosPublisher::SetRosHandle(ros::NodeHandle *node_handle)
{
    _node_handle = node_handle;
}

void RosPublisher::init(const string &out_pose_topic,
                        const string &out_cloud_topic)
{
    if(out_cloud_topic.size()){
        publisher_clouds_ =
            _node_handle->advertise<CloudT>(out_cloud_topic, _msg_queue_size, false);
    }
    if(out_pose_topic.size()){
        publisher_odom_ =
            _node_handle->advertise<PathT>(out_pose_topic, _msg_queue_size, false);
    }
    string topic_model = Parameter::Instance()->GetModelTopic();
    path_.header.frame_id = "map";
    if(topic_model.size()){
        // publisher_model_ =
        //     _node_handle->advertise<ModelT>(topic_model, _msg_queue_size, false);
        // model_.reset(new ModelT);
        // model_->mesh_resource = "file:///home/juefx/Documents/Car-Model/Car.obj";
        // model_->id = -1;
        // model_->header.frame_id = "map";
        // model_->type = ModelT::MESH_RESOURCE;
        // model_->action = ModelT::ADD;
        // model_->lifetime = ros::Duration();
        // model_->color.r = 1.0;  model_->color.g = 1.0;
        // model_->color.b = 1.0; model_->color.a = 1.0;

        // model_->scale.x = 0.85; model_->scale.y = 0.9; model_->scale.z = 1.0;
        // modelOriginQ_ = Matrix3d(
        //             AngleAxisd(M_PI / 2, Vector3d::UnitZ())
        //         * AngleAxisd(0, Vector3d::UnitY())
        //         * AngleAxisd(M_PI / 2, Vector3d::UnitX()));
    }
}

void RosPublisher::load()
{
    PublishMap();
}

void RosPublisher::PublishPose(const IsometryData &pose)
{
    if(pose.timestamp <= lastTime){
        return;
    }
    Vector3d slamStart = Parameter::Instance()->GetSlamStart();
    Vector2d localToSlamstart = Parameter::Instance()->GetLocalToSlamstart();
    geometry_msgs::PoseStamped outputPose;
    outputPose.pose.position.x = pose.pose.translation().x() - localToSlamstart.x();
    outputPose.pose.position.y = pose.pose.translation().y() - localToSlamstart.y();
    outputPose.pose.position.z = pose.pose.translation().z() - slamStart.z();
    Quaterniond q(pose.pose.linear());
    outputPose.pose.orientation.w = q.w();
    outputPose.pose.orientation.x = q.x();
    outputPose.pose.orientation.y = q.y();
    outputPose.pose.orientation.z = q.z();
    outputPose.header.frame_id = "map";
    outputPose.header.stamp.fromSec(pose.timestamp);
    path_.header.stamp.fromSec(pose.timestamp);
    path_.poses.push_back(outputPose);
    publisher_odom_.publish(path_);
    lastTime = pose.timestamp;

    if(path_.poses.size() > 30000){
        path_.poses.erase(path_.poses.begin());
    }
    //////////////////////////
    /// \brief flu
    ///
    auto rpy= RotationQuaternionToEulerVector(q);
    std::ofstream ofs(Parameter::Instance()->GetBaseDir() + "/MapPose.txt", ios::app);
    ofs << setprecision(15) << pose.timestamp << ", " << outputPose.pose.position.x
        << ", " << outputPose.pose.position.y << ", " << outputPose.pose.position.z
        << ", " << q.w() << ", " << q.x() << ", "
        << q.y() << ", " << q.z() << ", " << rpy.x() << ", "
        << rpy.y() << ", " << rpy.z() << endl;
    //////////////////////////
    /// \brief rfu
    ///
//    q = q * AngleAxisd(-M_PI / 2, Vector3d::UnitZ());
////    auto halfPi = M_PI * 0.5;
//    auto rpy= RotationQuaternionToEulerVector(q);
//    std::ofstream ofs(Parameter::Instance()->GetBaseDir() + "/MapPose.txt", ios::app);
//    ofs << setprecision(15) << pose.timestamp << ", " << outputPose.pose.position.x
//        << ", " << outputPose.pose.position.y << ", " << outputPose.pose.position.z
//        << ", " << q.w() << ", " << q.x() << ", "
//        << q.y() << ", " << q.z() << ", " << rpy.x() << ", "
//        << rpy.y() << ", " << rpy.z() << endl;

    ofs.close();
}

void RosPublisher::PublishCloud(const PointCloudJ &cloud)
{
    publisher_clouds_.publish(CloudToRosCloud(boost::make_shared<PointCloudJ>(cloud)));
}

CloudT::Ptr RosPublisher::CloudToRosCloud(
        const PointCloudJ::ConstPtr &pointcloud)
{
    pcl::PCLPointCloud2 pcl_pc2;
    pcl::toPCLPointCloud2(*pointcloud, pcl_pc2);
    CloudT::Ptr ret(new CloudT);
    pcl_conversions::fromPCL(pcl_pc2, *ret);
    ret->header.frame_id = "map";
    return ret;
}

void RosPublisher::PublishMap()
{
    publisher_map_ =
        _node_handle->advertise<CloudT>("/map", _msg_queue_size, true);
    // string pcdCartDir = Parameter::Instance()->GetBaseDir() + "/pcd_cart/";
    string pcdCartDir = Parameter::Instance()->GetBaseDir();
    boost::filesystem::directory_iterator it(pcdCartDir);
    LOG(INFO) << "pcdCartDir: " << pcdCartDir;
    boost::filesystem::directory_iterator end;
    PointCloudJ pc;
    for(; it != end; it++) {
        if(it->path().extension().string() != ".pcd"){
            continue;
        }
        string pcdPath = it->path().string();
        LOG(INFO) << "pcdPath: " << pcdPath;
        PointCloudJ::Ptr cloud(new PointCloudJ);
        pcl::io::loadPCDFile(pcdPath, *cloud);
        PointCloudJ cloud1;
        for(size_t i = 0; i < cloud->size(); i++){
            if(i % 2 == 0){
                cloud1.push_back(cloud->at(i));
            }
        }
        pc += cloud1;
    }
    publisher_map_.publish(CloudToRosCloud(boost::make_shared<PointCloudJ>(pc)));
}


} // end of namespace