.. _program_listing_file__tmp_ws_src_aruco_ros_aruco_ros_include_aruco_ros_aruco_ros_utils.hpp: Program Listing for File aruco_ros_utils.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/aruco_ros/aruco_ros/include/aruco_ros/aruco_ros_utils.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // NOLINT(legal/copyright) #ifndef ARUCO_ROS__ARUCO_ROS_UTILS_HPP_ #define ARUCO_ROS__ARUCO_ROS_UTILS_HPP_ #include #include "aruco/aruco.h" #include "geometry_msgs/msg/pose_stamped.hpp" #include "sensor_msgs/msg/camera_info.hpp" #include "sensor_msgs/msg/image.hpp" #include "tf2/LinearMath/Transform.h" #include "tf2/transform_datatypes.h" #include "visualization_msgs/msg/marker.hpp" namespace aruco_ros { aruco::CameraParameters rosCameraInfo2ArucoCamParams( const sensor_msgs::msg::CameraInfo & cam_info, bool useRectifiedParameters); tf2::Transform arucoMarker2Tf2(const aruco::Marker & marker); std::vector detectMarkers( const cv::Mat & img, const aruco::CameraParameters & cam_params, float marker_size, aruco::MarkerDetector * detector = nullptr, bool normalize_ilumination = false, bool correct_fisheye = false); visualization_msgs::msg::Marker visMarkerFromPose( const geometry_msgs::msg::PoseStamped & pose, double marker_size, int marker_id = 1); } // namespace aruco_ros #endif // ARUCO_ROS__ARUCO_ROS_UTILS_HPP_