ROS 学习系列 -- 动态程序控制Rviz眼睛位置和目的焦点

在ROS开发中,我们经常需要使用Rviz去观察机器人运行的状态,但是手工控制往往观察位置和焦点是不够灵活的,我们需要程序自动控制改变Rviz的行为。这个的具体实现插件就是 rviz_animated_view_controller


首先安装

sudo apt-get install ros-indigo-rviz-animated-view-controller

在程序中只需要向 topic   /rviz/camera_placement 发送  view_controller_msgs::CameraPlacement 消息即可。


include文件

#include <ros/ros.h>
#include <tf/tf.h>
#include <stdlib.h>
#include <view_controller_msgs/CameraPlacement.h>

using namespace visualization_msgs;
using namespace std;



发送消息:将观察眼睛位置放在(200,200,200)观察(100,100,100)位置的物体

ros::Publisher rviz_camera_pub =
              node.advertise<view_controller_msgs::CameraPlacement>("/rviz/camera_placement", 10);

view_controller_msgs::CameraPlacement camera;
geometry_msgs::Point pt;
pt.x = 200; pt.y = 200; pt.z = 200;
camera.eye.point = pt;
camera.eye.header.frame_id = "base_link";
pt.x = 100 ; pt.y = 100; pt.z = 100;
camera.focus.point = pt;
camera.focus.header.frame_id = "base_link";

geometry_msgs::Vector3 up;
up.x = 0; up.y = 0; up.z = 10;
camera.up.vector = up;
camera.up.header.frame_id = "base_link";
camera.time_from_start = ros::Duration();
rviz_camera_pub.publish(camera);


在Rviz中设置激活插件,将下面的代码写入.rviz文件并在rviz中加载, 这段代码需要替换 Visualization Manager的Views组配置

Views:
    Current:
      Class: rviz_animated_view_controller/Animated
      Control Mode: Orbit
      Distance: 18.0018
      Enable Stereo Rendering:
        Stereo Eye Separation: 0.06
        Stereo Focal Distance: 1
        Swap Stereo Eyes: false
        Value: false
      Eye:
        X: -6.91897
        Y: 2.32315
        Z: 9.71209
      Focus:
        X: 8
        Y: 5
        Z: 0
      Maintain Vertical Axis: true
      Mouse Enabled: true
      Name: Current View
      Near Clip Distance: 0.01
      Placement Topic: /rviz/camera_placement
      Target Frame: <Fixed Frame>
      Transition Time: 0.5
      Up:
        X: 0
        Y: 0
        Z: 1
      Value: Animated (rviz_animated_view_controller)
    Saved: ~


 


  • 0
    点赞
  • 4
    收藏
    觉得还不错? 一键收藏
  • 2
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值