RM2023_SENTRY_NAV/rm_serial/include/rm_trans.hpp

41 lines
1.0 KiB
C++

//
// Created by hshine on 22-12-31.
//
#ifndef RM_SERIAL_RM_TRANS_HPP
#define RM_SERIAL_RM_TRANS_HPP
#include "geometry_msgs/PointStamped.h"
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/message_filter.h"
#include "message_filters/subscriber.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
#include "tf2/LinearMath/Quaternion.h"
#include "visualization_msgs/Marker.h"
#include "rm_serial/gimbal_msg.h"
#include "tf/tf.h"
#include <cmath>
namespace rm_trans {
class RMtrans {
public:
RMtrans();
void msgCallback(const geometry_msgs::PointStampedConstPtr& point_ptr);
private:
std::string target_frame_;
tf2_ros::Buffer buffer_;
tf2_ros::TransformListener tf2_trans_;
ros::NodeHandle nh_;
message_filters::Subscriber<geometry_msgs::PointStamped> point_sub_;
tf2_ros::MessageFilter<geometry_msgs::PointStamped> tf2_filter_;
visualization_msgs::Marker target_marker_msg_;
ros::Publisher target_marker_pub_;
ros::Publisher fire_marker_pub_;
ros::Publisher gimbal_cmd_pub_;
};
} // namespace rm_trans
#endif // RM_SERIAL_RM_TRANS_HPP