Skip to content

Commit

Permalink
Add files for gnss_poser
Browse files Browse the repository at this point in the history
  • Loading branch information
makotoyoshigoe committed Aug 22, 2024
1 parent a396d32 commit 4dfd07b
Show file tree
Hide file tree
Showing 3 changed files with 136 additions and 0 deletions.
4 changes: 4 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,10 @@ ament_auto_add_executable(gauss_kruger_node
src/GaussKruger.cpp
)

ament_auto_add_executable(gnss_poser
src/GnssPoser.cpp
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
set(ament_cmake_copyright_FOUND TRUE)
Expand Down
41 changes: 41 additions & 0 deletions include/gnss2map/GnssPoser.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// SPDX-FileCopyrightText: 2024 MakotoYoshigoe
// SPDX-License-Identifier: Apache-2.0

#ifndef GNSS2MAP__GNSSPOSER_HPP_
#define GNSS2MAP__GNSSPOSER_HPP_

#include <rclcpp/rclcpp.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
#include <string>

namespace gnss2map
{
class GnssPoser : public rclcpp::Node
{
public:
GnssPoser();
~GnssPoser();
void gnss_pose_callback(geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg);
void ekf_pose_callback(geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg);
void loop(void);
void declare_params(void);
void init_pub_sub(void);
void set_gnss_info(void);
void set_ekf_info(void);
double get_pub_rate(void);

private:
rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr pub_gnss_ekf_pose_with_covariance_;
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr sub_ekf_pose_with_covariance_;
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr sub_gnss_pose_with_covariance_;
bool ekf_first_receive_;
geometry_msgs::msg::PoseWithCovarianceStamped gnss_ekf_pose_with_covariance_;
geometry_msgs::msg::PoseWithCovarianceStamped ekf_pose_with_covariance_;
geometry_msgs::msg::PoseWithCovarianceStamped gnss_pose_with_covariance_;
std::string frame_id_;
double pub_rate_;
};
}

#endif // GNSS2MAP__GNSSPOSER_HPP_
91 changes: 91 additions & 0 deletions src/GnssPoser.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
// SPDX-FileCopyrightText: 2024 MakotoYoshigoe
// SPDX-License-Identifier: Apache-2.0

#include "gnss2map/GnssPoser.hpp"

namespace gnss2map
{
GnssPoser::GnssPoser() : Node("gnss_poser")
{
declare_params();
init_pub_sub();
}

GnssPoser::~GnssPoser(){}

void GnssPoser::declare_params(void)
{
declare_parameter("frame_id", "map");
get_parameter("frame_id", frame_id_);
declare_parameter("pub_rate", 10.0);
get_parameter("pub_rate", pub_rate_);
ekf_first_receive_ = false;
}

void GnssPoser::init_pub_sub(void)
{
pub_gnss_ekf_pose_with_covariance_ = create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>("gnss_ekf_pose_with_covariance", 2);
sub_gnss_pose_with_covariance_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
"gnss_pose_with_covariance", 2, std::bind(&GnssPoser::gnss_pose_callback, this, std::placeholders::_1)
);
sub_ekf_pose_with_covariance_ = create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
"ekf_pose_with_covariance", 2, std::bind(&GnssPoser::ekf_pose_callback, this, std::placeholders::_1)
);

}

void GnssPoser::gnss_pose_callback(geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg)
{
gnss_pose_with_covariance_ = *msg;
}

void GnssPoser::ekf_pose_callback(geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr msg)
{
if(!ekf_first_receive_) ekf_first_receive_ = true;
ekf_pose_with_covariance_ = *msg;
}

void GnssPoser::set_gnss_info()
{
gnss_ekf_pose_with_covariance_.pose.pose.position = gnss_pose_with_covariance_.pose.pose.position;
gnss_ekf_pose_with_covariance_.pose.covariance[0] = gnss_pose_with_covariance_.pose.covariance[0];
gnss_ekf_pose_with_covariance_.pose.covariance[7] = gnss_pose_with_covariance_.pose.covariance[7];
gnss_ekf_pose_with_covariance_.pose.covariance[14] = gnss_pose_with_covariance_.pose.covariance[14];
}

void GnssPoser::set_ekf_info()
{
gnss_ekf_pose_with_covariance_.pose.pose.orientation = ekf_pose_with_covariance_.pose.pose.orientation;
gnss_ekf_pose_with_covariance_.pose.covariance[21] = ekf_pose_with_covariance_.pose.covariance[21];
gnss_ekf_pose_with_covariance_.pose.covariance[28] = ekf_pose_with_covariance_.pose.covariance[28];
gnss_ekf_pose_with_covariance_.pose.covariance[35] = ekf_pose_with_covariance_.pose.covariance[35];
}

double GnssPoser::get_pub_rate(){
return pub_rate_;
}

void GnssPoser::loop(void)
{
if(!ekf_first_receive_) return;
gnss_ekf_pose_with_covariance_.header.frame_id = frame_id_;
gnss_ekf_pose_with_covariance_.header.stamp = now();
set_gnss_info();
set_ekf_info();
pub_gnss_ekf_pose_with_covariance_->publish(gnss_ekf_pose_with_covariance_);
}
}

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
auto node = std::make_shared<gnss2map::GnssPoser>();
rclcpp::Rate rate(node->get_pub_rate());
while(rclcpp::ok()){
node->loop();
rclcpp::spin_some(node);
rate.sleep();
}
rclcpp::shutdown();
return 0;
}

0 comments on commit 4dfd07b

Please sign in to comment.