鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    使用rviz2中的PointCloud打点Status:Error

    已定时 已固定 已锁定 已移动
    ROS 2相关问题
    ros2 rviz2 pointcloud打点
    2
    8
    862
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • 22356740442
      ”╰+gǒが油メo ╬▍
      最后由 小鱼 编辑

      原码如下:

      #include "rclcpp/rclcpp.hpp"
      #include "std_msgs/msg/string.hpp"
      #include "std_msgs/msg/u_int32.hpp"
      #include "sensor_msgs/point_cloud_conversion.hpp"
      #include "sensor_msgs/point_cloud2_iterator.hpp"
      #include <chrono>
      #include <memory>
      
      using namespace std::chrono_literals;
      using namespace geometry_msgs;
      
      using std::placeholders::_1;
      using std::placeholders::_2;
      
      /*
          创建一个类节点,名字叫做SingleDogNode,继承自Node.
      */
      class SingleDogNode : public rclcpp::Node
      {
      
      public:
          // 构造函数,有一个参数为节点名称
          SingleDogNode(std::string name) : Node(name)
          {
              publisher_ = this->create_publisher<sensor_msgs::msg::PointCloud>("multi_points", 10);
              timer_ = this->create_wall_timer(1s, std::bind(&SingleDogNode::timer_callback, this));
          }
      
      private:
          rclcpp::TimerBase::SharedPtr timer_;
          sensor_msgs::msg::PointCloud point_data;
          rclcpp::Publisher<sensor_msgs::msg::PointCloud>::SharedPtr publisher_;
          char count_x = 0;
          char count_y = 0;
          void timer_callback()
          {
              geometry_msgs::msg::Point32 p;
              p.x = count_x;
              p.y = count_y;
              p.z = 0;
              point_data.points.push_back(p);
              publisher_->publish(point_data);
              count_x++;
              count_y++;
          }
      };
      
      int main(int argc, char **argv)
      {
          rclcpp::init(argc, argv);
          /*产生一个Wang2的节点*/
          auto node = std::make_shared<SingleDogNode>("li4");
          /* 运行节点,并检测退出信号*/
          rclcpp::spin(node);
          rclcpp::shutdown();
          return 0;
      }
      

      运行结果:
      f7118063-7b63-44db-ad14-19fb5cb98213-image.png

      工程目录
      ac06fe6d-6ddd-4fb7-a19c-17d972aecc3a-image.png

      请问是哪一块出问题了😳

      小鱼小 2 条回复 最后回复 回复 引用 0
      • 小鱼小
        小鱼 技术大佬 @2235674044
        最后由 编辑

        @2235674044 看错误很简单,fixedframe为map的时候tf变换不到这个坐标系,所以你应该重新选一个fixedframe即可。

        新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

        22356740442 1 条回复 最后回复 回复 引用 0
        • 22356740442
          ”╰+gǒが油メo ╬▍ @小鱼
          最后由 编辑

          @小鱼 你好 这个怎么重新选一个fixedframe呢3ded0644-2722-4945-a187-a85ee575ce88-image.png

          1 条回复 最后回复 回复 引用 0
          • 小鱼小
            小鱼 技术大佬 @2235674044
            最后由 编辑

            @2235674044 在 使用rviz2中的PointCloud打点Status:Error 中说:

            point_data

            在你的程序,这个数据里应该可以给frame_id进行赋值,赋一个字符串,接着你在修改rviz2中第一栏frame_id保持和程序中的相同即可

            新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

            22356740442 1 条回复 最后回复 回复 引用 0
            • 22356740442
              ”╰+gǒが油メo ╬▍ @小鱼
              最后由 编辑

              @小鱼 请问ros2中怎么给话题的frame_id赋值呢

              小鱼小 1 条回复 最后回复 回复 引用 0
              • 小鱼小
                小鱼 技术大佬 @2235674044
                最后由 编辑

                @2235674044 look

                fishros@fishros-MS-7D42:~$ ros2 interface show sensor_msgs/msg/PointCloud
                ## THIS MESSAGE IS DEPRECATED AS OF FOXY
                ## Please use sensor_msgs/PointCloud2
                
                # This message holds a collection of 3d points, plus optional additional
                # information about each point.
                
                # Time of sensor data acquisition, coordinate frame ID.
                std_msgs/Header header
                	builtin_interfaces/Time stamp
                		int32 sec
                		uint32 nanosec
                	string frame_id
                
                # Array of 3d points. Each Point32 should be interpreted as a 3d point
                # in the frame given in the header.
                geometry_msgs/Point32[] points
                	#
                	#
                	float32 x
                	float32 y
                	float32 z
                
                # Each channel should have the same number of elements as points array,
                # and the data in each channel should correspond 1:1 with each point.
                # Channel names in common practice are listed in ChannelFloat32.msg.
                ChannelFloat32[] channels
                	#
                	string name
                	float32[] values
                
                

                so

                    rclcpp::TimerBase::SharedPtr timer_;
                    sensor_msgs::msg::PointCloud point_data;
                    point_data.header.frame_id = "你的frameid";
                    rclcpp::Publisher<sensor_msgs::msg::PointCloud>::SharedPtr publisher_;
                    char count_x = 0;
                    char count_y = 0;
                

                新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                22356740442 1 条回复 最后回复 回复 引用 0
                • 22356740442
                  ”╰+gǒが油メo ╬▍ @小鱼
                  最后由 编辑

                  @小鱼 解决了 感谢大佬😁

                  小鱼小 1 条回复 最后回复 回复 引用 0
                  • 小鱼小
                    小鱼 技术大佬 @2235674044
                    最后由 编辑

                    @2235674044 基操勿6

                    新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                    1 条回复 最后回复 回复 引用 0
                    • 第一个帖子
                      最后一个帖子
                    皖ICP备16016415号-7
                    Powered by NodeBB | 鱼香ROS