概要
オジリナルのロボットカート(ロボット台車)を設計・製作し、それをROSで動かします。
1)オリジナルのロボットカートを3D CADで設計します。
2)ROSの環境でロボットカートを表示したりシミュレーションしたりします。
3)ROSからロボットカートの実機を動かします。
2)ROSの環境でロボットカートを表示したりシミュレーションしたりします。
3)ROSからロボットカートの実機を動かします。
動画
ロボットカートの設計
3次元CADのSolidWorksを使用して、ロボットカートを設計します。車輪のモータにはマクソン社のエンコーダ付きブラシレスモータを使用しました。ロボットカートのフレームは、木材で設計しました。
ROSではロボットをURDFで表現します。URDFにロボットのデータを渡すために、SolidWorksからパーツをSTL形式で出力します。出力フォーマットはバイナリです。
このとき、オプションにて、単位をメートル、座標軸をROSで組み立てやすい場所に設定してから、STLファイルを出力します。
link要素とjoint要素を使用して、SolidWorksで出力したパーツを組み立てていき、ロボットカートのURDFを完成させます。
ロボットカートのURDFファイル hajimecart.urdf
<?xml version="1.0"?> <robot name="hajimecart"> <link name="base_footprint"/> <link name="base_link"> <visual> <geometry> <mesh filename="package://hajimecart_description/meshes/hr56_cart_body.stl" /> </geometry> <origin xyz="0 0 0.055" rpy="0 0 0"/> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <geometry> <mesh filename="package://hajimecart_description/meshes/hr56_cart_body_col.stl" /> </geometry> <origin xyz="0 0 0.055" rpy="0 0 0"/> </collision> <inertial> <mass value="1.65081"/> <origin xyz="-8.0e-6 0 0.033177" rpy="0 0 0"/> <inertia ixx="0.006051" iyy="0.00916" izz="0.009098" ixy="0" ixz="-1.0e-6" iyz="0"/> </inertial> </link> <joint name="base_joint" type="fixed"> <origin xyz="0 0 0" rpy="0 0 0"/> <parent link="base_footprint"/> <child link="base_link" /> </joint> <link name="right_wheel_link"> <visual> <geometry> <mesh filename="package://hajimecart_description/meshes/wheel.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <geometry> <mesh filename="package://hajimecart_description/meshes/wheel_col.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> </collision> <inertial> <mass value="0.376"/> <origin xyz="0 -0.030687 0" rpy="0 0 0"/> <inertia ixx="0.001305" iyy="0.0016" izz="0.001305" ixy="0" ixz="0" iyz="0"/> </inertial> </link> <joint name="right_wheel_joint" type="continuous"> <origin xyz="0 -0.09 0.085" rpy="0 0 0"/> <axis xyz="0 1 0"/> <parent link="base_link"/> <child link="right_wheel_link"/> </joint> <link name="left_wheel_link"> <visual> <geometry> <mesh filename="package://hajimecart_description/meshes/wheel.stl" /> </geometry> <origin xyz="0 0 0" rpy="3.141592654 0 0"/> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <geometry> <mesh filename="package://hajimecart_description/meshes/wheel_col.stl" /> </geometry> <origin xyz="0 0 0" rpy="3.141592654 0 0"/> </collision> <inertial> <mass value="0.376"/> <origin xyz="0 0.030687 0" rpy="0 0 0"/> <inertia ixx="0.001305" iyy="0.0016" izz="0.001305" ixy="0" ixz="0" iyz="0"/> </inertial> </link> <joint name="left_wheel_joint" type="continuous"> <origin xyz="0 0.09 0.085" rpy="0 0 0"/> <axis xyz="0 1 0"/> <parent link="base_link"/> <child link="left_wheel_link"/> </joint> <link name="right_caster_body_link"> <visual> <geometry> <mesh filename="package://hajimecart_description/meshes/caster_body.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <geometry> <mesh filename="package://hajimecart_description/meshes/caster_body_col.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> </collision> <inertial> <mass value="0.015"/> <origin xyz="-0.00321 0 -0.008862" rpy="0 0 0"/> <inertia ixx="3.0e-6" iyy="3.0e-6" izz="2.0e-6" ixy="0" ixz="1.0e-6" iyz="0"/> </inertial> </link> <joint name="right_caster_body_joint" type="continuous"> <origin xyz="0.236 -0.118 0.05" rpy="0 0 0"/> <axis xyz="0 0 1"/> <parent link="base_link"/> <child link="right_caster_body_link"/> </joint> <link name="left_caster_body_link"> <visual> <geometry> <mesh filename="package://hajimecart_description/meshes/caster_body.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <geometry> <mesh filename="package://hajimecart_description/meshes/caster_body_col.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> </collision> <inertial> <mass value="0.015"/> <origin xyz="-0.00321 0 -0.008862" rpy="0 0 0"/> <inertia ixx="3.0e-6" iyy="3.0e-6" izz="2.0e-6" ixy="0" ixz="1.0e-6" iyz="0"/> </inertial> </link> <joint name="left_caster_body_joint" type="continuous"> <origin xyz="0.236 0.118 0.05" rpy="0 0 0"/> <axis xyz="0 0 1"/> <parent link="base_link"/> <child link="left_caster_body_link"/> </joint> <link name="right_caster_wheel_link"> <visual> <geometry> <mesh filename="package://hajimecart_description/meshes/caster_wheel.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <geometry> <mesh filename="package://hajimecart_description/meshes/caster_wheel.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> </collision> <inertial> <mass value="0.01"/> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="1.0e-6" iyy="1.0e-6" izz="1.0e-6" ixy="0" ixz="0" iyz="0"/> </inertial> </link> <joint name="right_caster_wheel_joint" type="continuous"> <origin xyz="-0.011 0 -0.0296" rpy="0 0 0"/> <axis xyz="0 1 0"/> <parent link="right_caster_body_link"/> <child link="right_caster_wheel_link"/> </joint> <link name="left_caster_wheel_link"> <visual> <geometry> <mesh filename="package://hajimecart_description/meshes/caster_wheel.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <geometry> <mesh filename="package://hajimecart_description/meshes/caster_wheel.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> </collision> <inertial> <mass value="0.01"/> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="1.0e-6" iyy="1.0e-6" izz="1.0e-6" ixy="0" ixz="0" iyz="0"/> </inertial> </link> <joint name="left_caster_wheel_joint" type="continuous"> <origin xyz="-0.011 0 -0.0296" rpy="0 0 0"/> <axis xyz="0 1 0"/> <parent link="left_caster_body_link"/> <child link="left_caster_wheel_link"/> </joint> <link name="base_scan"> <visual> <geometry> <mesh filename="package://hajimecart_description/meshes/rplidar.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> <material name="white"> <color rgba="1 1 1 1"/> </material> </visual> <collision> <geometry> <mesh filename="package://hajimecart_description/meshes/rplidar_col.stl" /> </geometry> <origin xyz="0 0 0" rpy="0 0 0"/> </collision> <inertial> <mass value="0.218"/> <origin xyz="0.01176 -0.000741 -0.020473" rpy="0 0 0"/> <inertia ixx="0.000184" iyy="0.000296" izz="0.000234" ixy="-1.0e-6" ixz="-6.9e-5" iyz="1.0e-6"/> </inertial> </link> <joint name="scan_joint" type="fixed"> <origin xyz="0.192 0 0.2306" rpy="0 0 0"/> <parent link="base_link"/> <child link="base_scan"/> </joint>
Gazeboシミュレーション用にdifferential_drive_controllerとjoint_state_publisherとLIDAR用にlaserを追加します。
hajimecart.urdfの続き
hajimecart.urdfの続き
<gazebo> <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so"> <leftJoint>left_wheel_joint</leftJoint> <rightJoint>right_wheel_joint</rightJoint> <robotBaseFrame>base_footprint</robotBaseFrame> <wheelSeparation>0.236</wheelSeparation> <wheelDiameter>0.17</wheelDiameter> <publishWheelJointState>true</publishWheelJointState> <legacyMode>false</legacyMode> <commandTopic>cmd_vel</commandTopic> <odometryTopic>odom</odometryTopic> <odometryFrame>odom</odometryFrame> <odometrySource>world</odometrySource> <publishOdomTF>true</publishOdomTF> <publishWheelTF>false</publishWheelTF> <publishTf>true</publishTf> <updateRate>30</updateRate> <wheelAcceleration>1</wheelAcceleration> <wheelTorque>10</wheelTorque> <rosDebugLevel>na</rosDebugLevel> </plugin> </gazebo> <gazebo> <plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so"> <jointName>right_caster_body_joint, left_caster_body_joint, right_caster_wheel_joint, left_caster_wheel_joint</jointName> </plugin> </gazebo> <gazebo reference="base_scan"> <sensor type="gpu_ray" name="rplidar"> <pose>0 0 0 0 0 0</pose> <visualize>false</visualize> <update_rate>5</update_rate> <ray> <scan> <horizontal> <samples>360</samples> <resolution>1</resolution> <min_angle>-3.14159265</min_angle> <max_angle>3.14159265</max_angle> </horizontal> </scan> <range> <min>0.15</min> <max>12.0</max> <resolution>0.12</resolution> </range> <noise> <type>gaussian</type> <mean>0.0</mean> <stddev>0.01</stddev> </noise> </ray> <plugin name="gpu_laser" filename="libgazebo_ros_gpu_laser.so"> <topicName>scan</topicName> <frameName>base_scan</frameName> </plugin> </sensor> </gazebo> </robot>
Gazeboのpluginsのlaserに注意が必要です。PCにGPUがない場合は、上のgpu_rayとlibgazebo_ros_gpu_laser.soを以下のrayとlibgazebo_ros_laser.soに置き換えたものを使用します。
<sensor type="ray" name="rplidar">
<plugin name="laser" filename="libgazebo_ros_laser.so">
STLファイルの中身にsolidの文字があれば警告が出ます。先頭にあるsolidの文字を、例えばsssssに置換します。
sed -i 's/^solid/sssss/' *
URDFをチェックします。
check_urdf urdf/hajimecart.urdf
ROSを起動しておきます。
roscore cd hajimecart_ws source devel/setup.bash
URDFチェックで問題なければrvizで表示して確認します。
cd src/hajimecart_description roslaunch urdf_tutorial display.launch model:=urdf/hajimecart.urdf gui:=true
joint_state_publisherのスライダーを動かすとロボットカートのjointが動きます。
ROSでロボットカートのシミュレーション
シミュレータのGazeboにロボットカートを表示させるために、以下をまとめたファイル(hajimecart.launch)を作成します。
1) gazebo_rosでhajimecart.urdfを生成します。
2) robot_state_publisherでロボットの状態を配信します。
hajimecart_gazebo.launch
<launch> <!-- Start Gazebo with an empty world --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="paused" value="false"/> <arg name="use_sim_time" value="true"/> <arg name="gui" value="true"/> <arg name="headless" value="false"/> <arg name="debug" value="false"/> </include> <!-- Load the HajimeCart URDF model into the parameter server --> <param name="robot_description" textfile="$(find hajimecart_description)/urdf/hajimecart.urdf" /> <!-- Spawn a HajimeCart in Gazebo, taking the description from the parameter server --> <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-param robot_description -urdf -model hajimecart" output="screen"/> <!-- Convert /joint_states messages published by Gazebo to /tf messages, e.g., for rviz--> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen"/> </launch>
シミュレーションで動かしてみます。Gazeboを起動します。
roslaunch hajimecart_description hajimecart_gazebo.launch
キーボードでロボットカートを操縦する場合は、このプログラムを起動します。
rosrun teleop_twist_keyboard teleop_twist_keyboard.py
起動時の画面
Reading from the keyboard and Publishing to Twist! --------------------------- Moving around: u i o j k l m , . For Holonomic mode (strafing), hold down the shift key: --------------------------- U I O J K L M < > t : up (+z) b : down (-z) anything else : stop q/z : increase/decrease max speeds by 10% w/x : increase/decrease only linear speed by 10% e/c : increase/decrease only angular speed by 10% CTRL-C to quit currently: speed 0.5 turn 1.0
ジョイパッドでロボットカートを操縦する場合は、ジョイパッドのデータを読み込むプログラムを起動します。
rosrun joy joy_node _dev:=/dev/input/js0
ジョイパッドでロボットカートを操縦する場合は、ジョイパッドのデータ(joy)をカートの速度指令(cmd_vel)に変換するプログラムを作成します。
joy_teleop.cpp
joy_teleop.cpp
#include <ros/ros.h> #include <geometry_msgs/Twist.h> #include <sensor_msgs/Joy.h> geometry_msgs::Twist cmd_vel; void joy_callback(const sensor_msgs::Joy& msg) { cmd_vel.linear.x = msg.axes[1]; cmd_vel.angular.z = msg.axes[0]; } int main(int argc, char** argv) { ros::init(argc, argv, "teleop_joy"); ros::NodeHandle nh; cmd_vel.linear.x = 0.0; cmd_vel.linear.y = 0.0; cmd_vel.linear.z = 0.0; cmd_vel.angular.x = 0.0; cmd_vel.angular.y = 0.0; cmd_vel.angular.z = 0.0; // publish ros::Publisher cmd_vel_pub = nh.advertise<geometry_msgs::Twist>("cmd_vel", 10); // subscriibe ros::Subscriber joy_sub = nh.subscribe("joy", 10, joy_callback); ros::Rate loop_rate(100); //100Hz(10ms) while (ros::ok()) { cmd_vel_pub.publish(cmd_vel); ros::spinOnce(); loop_rate.sleep(); } return 0; }
ジョイパッドでカートを操縦する場合は、上で作成したプログラムを起動します。
rosrun joy_teleop joy_teleop
rvizを起動します。
roslaunch urdf_tutorial display.launch model:=urdf/hajimecart.urdf gui:=false
Gazeboシミュレーション画面のカートの前方に円柱を追加します。
rviz画面にLaserScanのトピックを追加すると、LIDARのシミュレーションで測定されたLaserScanのデータが赤い点で円弧状に表示されます(下図の左側画面)。
LaserScanのデータを表示します。
rostopic echo /scan
header: seq: 133 stamp: secs: 53 nsecs: 925000000 frame_id: "base_scan" angle_min: -3.14159011841 angle_max: 3.14159011841 angle_increment: 0.0175018943846 time_increment: 0.0 scan_time: 0.0 range_min: 0.15000000596 range_max: 12.0 ranges: [inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, 3.236022472381592, 3.1493988037109375, 3.093291997909546, 3.0535807609558105, 3.0251283645629883, 3.005448341369629, 2.993204116821289, 2.987684726715088, 2.988595962524414, 2.995985269546509, 3.010253429412842, 3.032259941101074, 3.0635933876037598, 3.1072609424591064, 3.1698343753814697, 3.2724905014038086, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf] intensities: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] ---
ROSのノードとトピックを表示します。
rqt_graph
ROSの座標変換TFを表示します。
rosrun tf view_frames
または
rosrun rqt_tf_tree rqt_tf_tree
ROSからロボットカートの実機を動作
ロボットカートの実機を動作させる場合は、hajimecart.urdfからGazeboに関わる部分を削除したものhajimecart_robothw.urdfを使います。
hajimecart.urdfからdifferential_drive_controllerとjoint_state_publisherとlaserを削除しました。
roslaunch urdf_tutorial display.launch model:=urdf/hajimecart_robothw.urdf gui:=false
PC(Intel NUC)とロボットカートとの接続は、mbedマイコンボード(Nucleo f401RE)を介して、ROSSerialで接続します。
mbedはオンラインコンパイラで開発できる。ROSserialを使うために、ros_lib_kineticライブラリをリンクします。
mbedのプログラムは、
1) PC(Intel NUC)から車輪の左右モータの速度指令を購読して、モータ駆動基板に送信します。
2) モータ駆動基板から車輪の左右エンコーダ値を受信して、PC(Intel NUC)に配信します。
以下にmbedの主要部分のプログラムを示します。
PCと通信するボーレートは230400bpsで行いました。
main.cpp
#include "mbed.h" /* Nucleo-F401RE */ /* ROS */ #include <ros.h> #include <std_msgs/Int32MultiArray.h> #include <std_msgs/Float32MultiArray.h> #include <ros/time.h> /******/ #include "func.h" #include "cycle_time.h" //#include "usart1.h" //#include "rtm.h" #include "cntr.h" #include "sq_start.h" #include "servo_dx.h" #include "usart2.h" /* ROS */ ros::NodeHandle nh; std_msgs::Int32MultiArray encoder_data; ros::Publisher encoder_pub("encoder", &encoder_data); /******/ DigitalOut myled(LED1); DigitalOut rs485dir(D3); RawSerial usart2(D10, D2, 921600); // tx, rx Ticker cycle_time; int usart1_i = 0; int usart2_i = 0; void led_fun( int ); /* ROS */ void motorDriver_setSpeed(double,double); void motorDriver_start(); void motorDriver_stop(); void messageCb(const std_msgs::Float32MultiArray& msg) { if ( (fabs((double)msg.data[0]) < 1.0e-5) && (fabs((double)msg.data[1]) < 1.0e-5) ) { motorDriver_stop(); } else { motorDriver_setSpeed( msg.data[0], msg.data[1] ); } } ros::Subscriber<std_msgs::Float32MultiArray> cmdmotorspeed_sub("cmdmotorspeed", &messageCb); Timer _timer; const double _pi = 3.141592654; double limit_fun(double in, double high, double low) { double out; if( in > high ) { out = high; } else if( in < low ) { out = low; } else { out = in; } return out; } void motorDriver_setSpeed(double vel_left, double vel_right) { // wheel velocities // double vel_left = (vx - th * base_width / 2.0) / wheel_radius; // [rad/s] // double vel_right = (vx + th * base_width / 2.0) / wheel_radius; // [rad/s] double vel_left_rpm = vel_left / (2.0 * _pi) * 60.0 * 100.0; /* 0.17=wheel diameter, 100=gear ratio */ double vel_right_rpm = -vel_right / (2.0 * _pi) * 60.0 * 100.0; /* 0.17=wheel diameter, 100=gear ratio */ // sign vel_left_rpm = limit_fun( vel_left_rpm, 4000.0, -4000.0); vel_right_rpm = limit_fun( vel_right_rpm, 4000.0, -4000.0); xv_servo_dx.goal_speed[0]=(long)(0x800 + vel_left_rpm * 0xFFF / 14000); // 1000rpm 0x0FFF(-7000_7000rpm) xv_servo_dx.goal_speed[1]=(long)(0x800 + vel_right_rpm * 0xFFF / 14000); // 1000rpm // xv_servo_dx.goal_speed[0]=0x800+292; // 1000rpm 0x0FFF(-7000_7000rpm) // xv_servo_dx.goal_speed[1]=0x800+292; // 1000rpm // xv_servo_dx.goal_speed[0]=0x800-292; // -1000rpm 0x0FFF(-7000_7000rpm) // xv_servo_dx.goal_speed[1]=0x800-292; // -1000rpm } void motorDriver_start() { motorDriver_setSpeed(0.0, 0.0); flag_sq_start = 1; } void motorDriver_stop() { motorDriver_setSpeed(0.0, 0.0); // flag_servo_off = 1; } ros::Time current_time, last_time; long vel_timer = 0; void ros_init1() { /* ROS */ encoder_data.data_length = 2; encoder_data.data = (int32_t *)malloc(sizeof(int32_t)*2); encoder_data.data[0] = 0; encoder_data.data[1] = 0; nh.getHardware()->setBaud(230400); nh.initNode(); nh.subscribe(cmdmotorspeed_sub); nh.advertise(encoder_pub); _timer.start(); } void ros_init2() { /* ROS */ vel_timer = _timer.read_ms() + 5000; read_encoder(); nh.loginfo("hajiimecart_mbed program start"); last_time = nh.now(); //ros::Time::now(); current_time = nh.now(); //ros::Time::now(); } void ros_fun1() { /* ROS */ nh.spinOnce(); // check for incoming messages current_time = nh.now(); //ros::Time::now(); encoder_data.data[0] = encoder_left; encoder_data.data[1] = encoder_right; encoder_pub.publish(&encoder_data); last_time = current_time; /* ROS */ if (_timer.read_ms() > vel_timer) { // motorDriver_stop(); vel_timer = _timer.read_ms() + 5000; } } int main() { led_fun( 1); wait_ms(1000); // 1000 ms led_fun( 0); /* ROS */ ros_init1(); var_init(); cycle_time_init(); usart2_init(); motorDriver_stop(); wait_ms(1000); // 3000 ms cycle_time.attach_us(cycle_time_fun, 40000); // 40msec /* ROS */ ros_init2(); while(1) { /******/ if( flag_cycle_time > 0 ) { /* ROS */ ros_fun1(); if( startup_time_count < ULONG_MAX ) { ++startup_time_count; } if( startup_time_count_us < USHORT_MAX ) { ++startup_time_count_us; } startup_time_count_f += RTC_TIME_SEC; if( startup_time_count == 50 ) { motorDriver_start(); } /*** user application program ***/ cntr(); /*** led ***/ FLICKER( 1, xv_flicker_out, RTC_TIME_TICK/2, xv_flicker_work ); led_fun( xv_flicker_out ); flag_cycle_time = 0; } } } /** * @brief Led on/off. * @param None * @retval None */ void led_fun( int a ) { if( a ) { myled = 1; // LED is ON } else { myled = 0; // LED is OFF } }
ROSserialの通信バッファサイズがデフォルトだと足りなくてエラーが出るので、10000に増やします。
ros_lib_kinetic/ros/node_handle.h(抜粋)
namespace ros { using rosserial_msgs::TopicInfo; /* Node Handle */ template <class Hardware, int MAX_SUBSCRIBERS=25, int MAX_PUBLISHERS=25, int INPUT_SIZE=10000, int OUTPUT_SIZE=10000>
PCとmbedを接続した後、rosserialを実行します。
rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0 _baud:=230400
または、Launchファイルで書くとこのようになります。
hajimecart_rosserial.launch
hajimecart_rosserial.launch
<launch> <node pkg="rosserial_python" type="serial_node.py" name="serial_node"> <param name="port" value="/dev/ttyACM0"/> <param name="baud" value="230400"/> </node> </launch>
これは、次のように実行します。
roslaunch teleop_joy hajimecart_rosserial.launch
PC(Intel NUC)では、
1) トピックcmd_velのTwistメッセージを購読して、車輪の左右モータの速度指令に換算して配信します。(作成したノード名cmdvel_cmdmotorspeed)
2)車輪の左右エンコーダ値を購読し、オドメトリを計算して、トピックodomと、TFを配信します。(作成したノード名odometry_publisher)
cmdvel_cmdmotorspeed.cpp
#include <ros/ros.h> #include <geometry_msgs/Twist.h> #include <std_msgs/Float32MultiArray.h> // HajimeCart parameter const double wheel_radius= 0.085; // wr const double base_width = 0.236; // ws std_msgs::Float32MultiArray cmdmotorspeed; // v_cmd = omega * R // V_right = v_cmd + omega * L / 2 // V_left = v_cmd + omega * L / 2 // v_cmd = msg.linear.x // omega = msg.angular.z // Apply (possibly new) multipliers: // const double ws = wheel_separation_multiplier_ * wheel_separation_; // const double lwr = left_wheel_radius_multiplier_ * wheel_radius_; // const double rwr = right_wheel_radius_multiplier_ * wheel_radius_; // Compute wheels velocities: // const double vel_left = (curr_cmd.lin - curr_cmd.ang * ws / 2.0)/wr; // const double vel_right = (curr_cmd.lin + curr_cmd.ang * ws / 2.0)/wr; // DEBUG dlimit vx,th // wheel velocities // double vel_left = (vx - th * base_width / 2.0) / wheel_radius; // [rad/s] // double vel_right = (vx + th * base_width / 2.0) / wheel_radius; // [rad/s] void cmd_vel_callback(const geometry_msgs::Twist& msg) { cmdmotorspeed.data[0] = (msg.linear.x - msg.angular.z * base_width / 2.0) / wheel_radius; // left motor [rad/s] cmdmotorspeed.data[1] = (msg.linear.x + msg.angular.z * base_width / 2.0) / wheel_radius; // right motor [rad/s] } int main(int argc, char** argv) { ros::init(argc, argv, "cmdvel_cmdmotorspeed"); ros::NodeHandle nh; cmdmotorspeed.data.resize(2); cmdmotorspeed.data[0] = 0.0; cmdmotorspeed.data[1] = 0.0; // publish ros::Publisher cmdmotorspeed_pub = nh.advertise<std_msgs::Float32MultiArray>("cmdmotorspeed", 10); // subscriibe ros::Subscriber cmd_vel_sub = nh.subscribe("cmd_vel", 10, cmd_vel_callback); while (ros::ok()) { cmdmotorspeed_pub.publish(cmdmotorspeed); ros::spinOnce(); loop_rate.sleep(); } return 0; }
odometry_publisher.cpp
#include <ros/ros.h> #include <std_msgs/Int32MultiArray.h> #include <tf/transform_broadcaster.h> #include <nav_msgs/Odometry.h> // HajimeCart parameter const double wheel_radius= 0.085; // wr const double base_width = 0.236; // ws const double _pi = 3.141592654; const double xp_enc_ticks_meter = 6250.0 / (2.0 * _pi * wheel_radius); double encoder_left = 0; double encoder_right = 0; double encoder_left_old = 0; double encoder_right_old = 0; double pos_x = 0.0; double pos_y = 0.0; double pos_th = 0.0; int flag_firsttime = 1; void encoderCallback(const std_msgs::Int32MultiArray::ConstPtr& msg); ros::Publisher odom_pub; int main(int argc, char** argv){ ros::init(argc, argv, "odometry_publisher"); ros::NodeHandle n; ros::Subscriber encoder_sub = n.subscribe("encoder", 10, encoderCallback); odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50); ros::spin(); // check for incoming messages return 0; } ros::Time current_time, last_time; void encoderCallback(const std_msgs::Int32MultiArray::ConstPtr& msg) { static tf::TransformBroadcaster odom_broadcaster; encoder_left = msg->data[0]; encoder_right = msg->data[1]; if( flag_firsttime ) { flag_firsttime = 0; encoder_left_old = encoder_left; encoder_right_old = encoder_right; last_time = ros::Time::now(); return; } current_time = ros::Time::now(); //compute odometry in a typical way given the velocities of the robot // double dt=((double)current_time.sec + 1e-9*(double)current_time.nsec) - ((double)last_time.sec + 1e-9*(double)last_time.nsec); double dt = (current_time - last_time).toSec(); double d_left = (encoder_left - encoder_left_old ) / xp_enc_ticks_meter; double d_right = (encoder_right - encoder_right_old ) / xp_enc_ticks_meter; encoder_left_old = encoder_left; encoder_right_old = encoder_right; double d = (d_left + d_right) / 2.0; double th = (d_right - d_left) / base_width; // calc dt becomes big for the first time double dx; double dr; if( dt < 1000.0 ) { dx = d / dt; dr = th / dt; } else { dt = 0.0; dx = 0; dr = 0; } if( fabs(d) > 1.0e-5 ) { double _x = cos(th) * d; double _y = -sin(th) * d; pos_x += (_x * cos(pos_th) - _y * sin(pos_th)); pos_y += (_x * sin(pos_th) + _y * cos(pos_th)); } if(fabs(th) > 1.0e-5 ) { pos_th += th; } // const double wr= 0.085; // const double ws = 0.236; // r = ws/2.0 * (encoder_left + encoder_right)/(encoder_right - encoder_left ); // omega_dt = (encoder_right - encoder_left) * step / ws // iccx = x - r * sin(theta) // iccy = y + r * cos(theta) // x_new = (x - iccx) * cos(omega_dt) - (y - iccy) * sin(omega_dt) + iccx; // y_new = (x - iccx) * sin(omega_dt) + (y - iccy) * cos(omega_dt) + iccy; // theta_new = theta + omega_dt; //since all odometry is 6DOF we'll need a quaternion created from yaw geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(pos_th); //first, we'll publish the transform over tf geometry_msgs::TransformStamped odom_trans; odom_trans.header.stamp = current_time; odom_trans.header.frame_id = "/odom"; odom_trans.child_frame_id = "/base_footprint"; odom_trans.transform.translation.x = pos_x; odom_trans.transform.translation.y = pos_y; odom_trans.transform.translation.z = 0.0; odom_trans.transform.rotation = odom_quat; //send the transform odom_broadcaster.sendTransform(odom_trans); //next, we'll publish the odometry message over ROS nav_msgs::Odometry odom; odom.header.stamp = current_time; odom.header.frame_id = "/odom"; //set the position odom.pose.pose.position.x = pos_x; odom.pose.pose.position.y = pos_y; odom.pose.pose.position.z = 0.0; odom.pose.pose.orientation = odom_quat; //set the velocity odom.child_frame_id = "/base_footprint"; odom.twist.twist.linear.x = dx; odom.twist.twist.linear.y = 0; odom.twist.twist.angular.z = dr; //publish the message odom_pub.publish(odom); last_time = current_time; }
これらのノードを起動します。
rosrun cmdvel_cmdmotorspeed cmdvel_cmdmotorspeed
rosrun odometry_publisher odometry_publisher
ジョイパッドを起動します。
rosrun joy joy_node _dev:=/dev/input/js0 rosrun hajimecart_teleop joy_teleop
rvizのfixed frameをodomにすると実機のロボットカートの動きに応じて画面上のロボットカートが動きます。
LIDAR
http://wiki.ros.org/rplidar
https://www.slamtec.com/en/Lidar/A1
「LIDARとは、光を用いたリモートセンシング技術の一つで、パルス状に発光するレーザー照射に対する散乱光を測定し、遠距離にある対象までの距離やその対象の性質を分析するものである。」https://ja.wikipedia.org/wiki/LIDAR から引用
LIDAR(LaserScan)のデータを読み込みます。
LIDARをPCに接続します。
LIDARのプログラムを起動します。
roslaunch rplidar_ros rplidar.launch
LIDARのLaunchファイルの、frame_idをlaserからbase_scanに変更しています。
rplidar.launch
<launch> <node name="rplidarNode" pkg="rplidar_ros" type="rplidarNode" output="screen"> <param name="serial_port" type="string" value="/dev/ttyUSB0"/> <param name="serial_baudrate" type="int" value="115200"/><!--A1/A2 --> <!--param name="serial_baudrate" type="int" value="256000"--><!--A3 --> <param name="frame_id" type="string" value="base_scan"/> <param name="inverted" type="bool" value="false"/> <param name="angle_compensate" type="bool" value="true"/> </node> </launch>
起動後のメッセージ
... logging to /home/sakamoto/.ros/log/cceaca0e-d509-11e9-9781-144f8ac75894/roslaunch-OMEN-23473.log Checking log directory for disk usage. This may take awhile. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB. started roslaunch server http://192.168.0.21:37927/ SUMMARY ======== PARAMETERS * /rosdistro: kinetic * /rosversion: 1.12.14 * /rplidarNode/angle_compensate: True * /rplidarNode/frame_id: base_scan * /rplidarNode/inverted: False * /rplidarNode/serial_baudrate: 115200 * /rplidarNode/serial_port: /dev/ttyUSB0 NODES / rplidarNode (rplidar_ros/rplidarNode) ROS_MASTER_URI=http://192.168.0.21:11311 /opt/ros/kinetic/lib/python2.7/dist-packages/roslib/packages.py:451: UnicodeWarning: Unicode equal comparison failed to convert both arguments to Unicode - interpreting them as being unequal if resource_name in files: process[rplidarNode-1]: started with pid [23491] [ INFO] [1568267240.170577586]: RPLIDAR running on ROS package rplidar_ros. SDK Version:1.10.0 RPLIDAR S/N: A0BB9AF2C1EA9FC2A2EB92F133683C00 [ INFO] [1568267242.680867539, 9163.445000000]: Firmware Ver: 1.27 [ INFO] [1568267242.680901775, 9163.445000000]: Hardware Rev: 5 [ INFO] [1568267242.682680913, 9163.447000000]: RPLidar health status : 0 [ INFO] [1568267243.223945774, 9163.987000000]: current scan mode: Standard, max_distance: 12.0 m, Point number: 2.0K , angle_compensate: 1
LIDARのクライアントを起動します。
rosrun rplidar_ros rplidarNodeClient
起動時の画面
[ INFO] [1565073329.987854212]: I heard a laser scan base_scan[-2147483648]: [ INFO] [1565073329.988028973]: angle_range, -178.999983, 180.000005 [ INFO] [1565073329.988101578]: : [-178.999985, 0.511000] [ INFO] [1565073329.988163889]: : [-177.999985, 0.514000] [ INFO] [1565073329.988258578]: : [-176.999985, 0.516000] [ INFO] [1565073329.988376745]: : [-175.999985, 0.518000] [ INFO] [1565073329.988443225]: : [-174.999985, 0.521000] [ INFO] [1565073329.988530633]: : [-173.999985, 0.524000] [ INFO] [1565073329.988605438]: : [-172.999969, 0.528000] [ INFO] [1565073329.988673797]: : [-171.999985, 0.529000] [ INFO] [1565073329.988741022]: : [-170.999985, 0.534000] [ INFO] [1565073329.988808010]: : [-169.999985, 0.537000] [ INFO] [1565073329.988873749]: : [-168.999985, 0.542000] [ INFO] [1565073329.988939801]: : [-167.999985, 0.544000] [ INFO] [1565073329.989004249]: : [-166.999985, 0.550000] [ INFO] [1565073329.989069656]: : [-165.999985, 0.552000] [ INFO] [1565073329.989147717]: : [-164.999985, 0.559000] [ INFO] [1565073329.989215427]: : [-163.999985, 0.562000] [ INFO] [1565073329.989280725]: : [-162.999985, 0.569000] [ INFO] [1565073329.989345867]: : [-161.999985, 0.572000] [ INFO] [1565073329.989416316]: : [-160.999985, 0.581000] [ INFO] [1565073329.989499299]: : [-159.999985, 0.588000] [ INFO] [1565073329.989574585]: : [-158.999985, 0.593000] [ INFO] [1565073329.989655867]: : [-157.999985, 0.602000] [ INFO] [1565073329.989731097]: : [-156.999985, 0.606000] [ INFO] [1565073329.989797282]: : [-155.999985, 0.617000] [ INFO] [1565073329.989874738]: : [-154.999985, 0.621000] [ INFO] [1565073329.989951712]: : [-153.999985, 0.633000] [ INFO] [1565073329.990024110]: : [-152.999985, 0.639000] [ INFO] [1565073329.990090682]: : [-151.999985, 0.651000] [ INFO] [1565073329.990160307]: : [-150.999985, 0.657000] [ INFO] [1565073329.990232111]: : [-149.999985, 0.671000] [ INFO] [1565073329.990298260]: : [-148.999969, 0.677000] [ INFO] [1565073329.990372552]: : [-147.999985, 0.694000] [ INFO] [1565073329.990439089]: : [-146.999985, 0.701000] [ INFO] [1565073329.990505944]: : [-145.999985, 0.710000] [ INFO] [1565073329.990574325]: : [-144.999985, 0.726000] [ INFO] [1565073329.990642931]: : [-143.999969, 0.744000] [ INFO] [1565073329.990707741]: : [-142.999985, 0.755000] [ INFO] [1565073329.990772720]: : [-141.999985, 0.465000] [ INFO] [1565073329.990838368]: : [-140.999985, 0.465000] [ INFO] [1565073329.990903003]: : [-139.999985, 0.458000] [ INFO] [1565073329.990969037]: : [-138.999985, 0.458000] [ INFO] [1565073329.991032461]: : [-137.999985, inf] [ INFO] [1565073329.991095725]: : [-136.999985, inf] [ INFO] [1565073329.991158793]: : [-135.999985, inf] [ INFO] [1565073329.991223100]: : [-134.999985, inf] [ INFO] [1565073329.991288155]: : [-133.999985, 0.388000] [ INFO] [1565073329.991352591]: : [-132.999985, 0.388000] [ INFO] [1565073329.991415081]: : [-131.999985, inf] [ INFO] [1565073329.991477672]: : [-130.999985, inf] [ INFO] [1565073329.991539533]: : [-129.999985, inf] [ INFO] [1565073329.991602964]: : [-128.999985, inf] [ INFO] [1565073329.991666498]: : [-127.999985, inf] [ INFO] [1565073329.991733316]: : [-126.999992, 0.932000] [ INFO] [1565073329.991816690]: : [-125.999985, 0.939000] [ INFO] [1565073329.991882035]: : [-124.999992, 0.933000] [ INFO] [1565073329.991947132]: : [-123.999977, 0.932000] [ INFO] [1565073329.992011610]: : [-122.999985, 0.957000] [ INFO] [1565073329.992075859]: : [-121.999992, 1.009000] [ INFO] [1565073329.992139829]: : [-120.999985, inf] [ INFO] [1565073329.992204390]: : [-119.999977, 1.582000] [ INFO] [1565073329.992292783]: : [-118.999985, 1.609000] [ INFO] [1565073329.992360688]: : [-117.999985, 1.656000] [ INFO] [1565073329.992469916]: : [-116.999992, inf] [ INFO] [1565073329.992533041]: : [-115.999985, 1.801000] [ INFO] [1565073329.992622519]: : [-114.999977, 1.974000] [ INFO] [1565073329.992690076]: : [-113.999985, inf] [ INFO] [1565073329.992752097]: : [-112.999985, inf] [ INFO] [1565073329.992812994]: : [-111.999985, 2.788000] [ INFO] [1565073329.992873409]: : [-110.999985, 2.796000] [ INFO] [1565073329.992933899]: : [-109.999985, 2.802000] [ INFO] [1565073329.992993299]: : [-108.999985, 3.431000] [ INFO] [1565073329.993053794]: : [-107.999985, 2.864000] [ INFO] [1565073329.993113077]: : [-106.999985, 2.827000] [ INFO] [1565073329.993172603]: : [-105.999985, 2.848000] [ INFO] [1565073329.993234273]: : [-104.999985, 2.844000] [ INFO] [1565073329.993295238]: : [-103.999985, 2.825000] [ INFO] [1565073329.993354751]: : [-102.999985, 2.847000] [ INFO] [1565073329.993414700]: : [-101.999985, 2.858000] [ INFO] [1565073329.993474494]: : [-100.999985, 2.851000] [ INFO] [1565073329.993535414]: : [-99.999985, 2.859000] [ INFO] [1565073329.993594806]: : [-98.999985, 2.860000] [ INFO] [1565073329.993657447]: : [-97.999985, 2.868000] [ INFO] [1565073329.993720104]: : [-96.999985, 2.882000] [ INFO] [1565073329.993779653]: : [-95.999985, 3.366000] [ INFO] [1565073329.993838625]: : [-94.999985, 3.369000] [ INFO] [1565073329.993902832]: : [-93.999985, 3.380000] [ INFO] [1565073329.993963996]: : [-92.999985, 3.374000] [ INFO] [1565073329.994023996]: : [-91.999985, 3.414000] [ INFO] [1565073329.994083938]: : [-90.999985, 3.411000] [ INFO] [1565073329.994143720]: : [-89.999985, 3.428000] [ INFO] [1565073329.994203997]: : [-88.999977, 3.381000] [ INFO] [1565073329.994263684]: : [-87.999985, 3.044000] [ INFO] [1565073329.994323362]: : [-86.999985, 2.887000] [ INFO] [1565073329.994382750]: : [-85.999985, 2.887000] [ INFO] [1565073329.994441965]: : [-84.999985, 2.900000] [ INFO] [1565073329.994502196]: : [-83.999985, 2.907000] [ INFO] [1565073329.994563149]: : [-82.999977, 2.932000] [ INFO] [1565073329.994622670]: : [-81.999985, 2.950000] [ INFO] [1565073329.994676119]: : [-80.999985, 2.964000] [ INFO] [1565073329.994736055]: : [-79.999985, 3.241000] [ INFO] [1565073329.994796698]: : [-78.999985, 3.603000] [ INFO] [1565073329.994855838]: : [-77.999985, 3.637000] [ INFO] [1565073329.994915597]: : [-76.999985, 3.651000] [ INFO] [1565073329.994974950]: : [-75.999985, 3.660000] [ INFO] [1565073329.995034208]: : [-74.999985, 3.597000] [ INFO] [1565073329.995093755]: : [-73.999985, 3.735000] [ INFO] [1565073329.995152491]: : [-72.999985, 3.747000] [ INFO] [1565073329.995211865]: : [-71.999985, 3.815000] [ INFO] [1565073329.995271127]: : [-70.999985, 3.826000] [ INFO] [1565073329.995330476]: : [-69.999985, 3.591000] [ INFO] [1565073329.995389779]: : [-68.999985, 3.670000] [ INFO] [1565073329.995449046]: : [-67.999985, 3.744000] [ INFO] [1565073329.995508854]: : [-66.999985, 3.766000] [ INFO] [1565073329.995568409]: : [-65.999985, 3.771000] [ INFO] [1565073329.995627572]: : [-64.999985, inf] [ INFO] [1565073329.995687165]: : [-63.999977, inf] [ INFO] [1565073329.995747915]: : [-62.999985, inf] [ INFO] [1565073329.995807731]: : [-61.999989, inf] [ INFO] [1565073329.995865948]: : [-60.999981, inf] [ INFO] [1565073329.995924914]: : [-59.999989, inf] [ INFO] [1565073329.995983678]: : [-58.999981, inf] [ INFO] [1565073329.996042512]: : [-57.999985, inf] [ INFO] [1565073329.996102549]: : [-56.999977, 3.521000] [ INFO] [1565073329.996162131]: : [-55.999985, 3.552000] [ INFO] [1565073329.996222570]: : [-54.999989, 3.603000] [ INFO] [1565073329.996304088]: : [-53.999981, 3.679000] [ INFO] [1565073329.996366622]: : [-52.999989, 3.717000] [ INFO] [1565073329.996426078]: : [-51.999977, 3.259000] [ INFO] [1565073329.996486218]: : [-50.999985, 3.288000] [ INFO] [1565073329.996545763]: : [-49.999989, 3.365000] [ INFO] [1565073329.996604260]: : [-48.999981, inf] [ INFO] [1565073329.996664254]: : [-47.999989, inf] [ INFO] [1565073329.996726878]: : [-46.999981, 2.989000] [ INFO] [1565073329.996786828]: : [-45.999985, 2.982000] [ INFO] [1565073329.996846233]: : [-44.999992, 3.088000] [ INFO] [1565073329.996905007]: : [-43.999985, 3.149000] [ INFO] [1565073329.996964209]: : [-42.999989, 3.263000] [ INFO] [1565073329.997023926]: : [-41.999981, 3.312000] [ INFO] [1565073329.997083875]: : [-40.999985, 3.424000] [ INFO] [1565073329.997143806]: : [-39.999977, 2.793000] [ INFO] [1565073329.997203078]: : [-38.999985, 2.861000] [ INFO] [1565073329.997262518]: : [-37.999989, 2.901000] [ INFO] [1565073329.997322749]: : [-36.999981, 3.042000] [ INFO] [1565073329.997382171]: : [-35.999989, 3.100000] [ INFO] [1565073329.997441336]: : [-34.999981, 3.208000] [ INFO] [1565073329.997501691]: : [-33.999985, 2.949000] [ INFO] [1565073329.997560598]: : [-32.999992, 3.019000] [ INFO] [1565073329.997620309]: : [-31.999983, 3.224000] [ INFO] [1565073329.997679476]: : [-30.999989, 3.504000] [ INFO] [1565073329.997740742]: : [-29.999981, 3.483000] [ INFO] [1565073329.997800530]: : [-28.999987, 3.479000] [ INFO] [1565073329.997860079]: : [-27.999977, 3.444000] [ INFO] [1565073329.997919675]: : [-26.999983, 3.409000] [ INFO] [1565073329.997979045]: : [-25.999989, 3.162000] [ INFO] [1565073329.998037952]: : [-24.999981, 3.178000] [ INFO] [1565073329.998097463]: : [-23.999987, 3.369000] [ INFO] [1565073329.998157024]: : [-22.999979, 3.359000] [ INFO] [1565073329.998216363]: : [-21.999985, 3.353000] [ INFO] [1565073329.998275444]: : [-20.999990, 3.338000] [ INFO] [1565073329.998335036]: : [-19.999983, 3.322000] [ INFO] [1565073329.998394618]: : [-18.999989, 3.324000] [ INFO] [1565073329.998452956]: : [-17.999981, 3.311000] [ INFO] [1565073329.998508897]: : [-16.999985, 3.275000] [ INFO] [1565073329.998562737]: : [-15.999991, 3.273000] [ INFO] [1565073329.998614887]: : [-14.999984, 3.263000] [ INFO] [1565073329.998668042]: : [-13.999989, 3.265000] [ INFO] [1565073329.998720411]: : [-12.999981, inf] [ INFO] [1565073329.998772881]: : [-11.999987, 3.283000] [ INFO] [1565073329.998825165]: : [-10.999979, 3.281000] [ INFO] [1565073329.998878106]: : [-9.999985, 3.285000] [ INFO] [1565073329.998929182]: : [-8.999990, 3.285000] [ INFO] [1565073329.998979550]: : [-7.999982, 3.288000] [ INFO] [1565073329.999029853]: : [-6.999988, 3.257000] [ INFO] [1565073329.999080588]: : [-5.999979, 3.266000] [ INFO] [1565073329.999131165]: : [-4.999985, 3.291000] [ INFO] [1565073329.999181650]: : [-3.999991, 3.309000] [ INFO] [1565073329.999231707]: : [-2.999983, 3.314000] [ INFO] [1565073329.999283379]: : [-1.999989, 3.321000] [ INFO] [1565073329.999335097]: : [-0.999981, 3.327000] [ INFO] [1565073329.999386057]: : [0.000014, 3.340000] [ INFO] [1565073329.999437285]: : [1.000022, 3.343000] [ INFO] [1565073329.999487744]: : [2.000016, 3.354000] [ INFO] [1565073329.999537947]: : [3.000010, 3.300000] [ INFO] [1565073329.999588132]: : [4.000018, 3.394000] [ INFO] [1565073329.999638187]: : [5.000013, 3.386000] [ INFO] [1565073329.999688387]: : [6.000021, 3.398000] [ INFO] [1565073329.999739094]: : [7.000015, 3.444000] [ INFO] [1565073329.999790591]: : [8.000010, inf] [ INFO] [1565073329.999841325]: : [9.000017, inf] [ INFO] [1565073329.999893449]: : [10.000011, 3.409000] [ INFO] [1565073329.999946360]: : [11.000020, 3.503000] [ INFO] [1565073329.999998341]: : [12.000014, 3.488000] [ INFO] [1565073330.000050996]: : [13.000022, 3.050000] [ INFO] [1565073330.000120919]: : [14.000016, 3.057000] [ INFO] [1565073330.000173697]: : [15.000010, 3.353000] [ INFO] [1565073330.000225245]: : [16.000019, inf] [ INFO] [1565073330.000302018]: : [17.000013, 0.906000] [ INFO] [1565073330.000432253]: : [18.000021, 0.897000] [ INFO] [1565073330.000485374]: : [19.000015, 0.904000] [ INFO] [1565073330.000560028]: : [20.000010, 0.913000] [ INFO] [1565073330.000625269]: : [21.000017, 0.928000] [ INFO] [1565073330.000652342]: : [22.000011, 0.941000] [ INFO] [1565073330.000679505]: : [23.000019, 0.964000] [ INFO] [1565073330.000706587]: : [24.000015, 0.977000] [ INFO] [1565073330.000732234]: : [25.000010, 1.000000] [ INFO] [1565073330.000758728]: : [26.000017, 1.013000] [ INFO] [1565073330.000785312]: : [27.000011, 1.036000] [ INFO] [1565073330.000812002]: : [28.000019, 1.047000] [ INFO] [1565073330.000843909]: : [29.000013, 1.071000] [ INFO] [1565073330.000870523]: : [30.000021, 1.081000] [ INFO] [1565073330.000897299]: : [31.000015, 1.109000] [ INFO] [1565073330.000923841]: : [32.000011, 1.119000] [ INFO] [1565073330.000950692]: : [33.000019, 0.669000] [ INFO] [1565073330.000977421]: : [34.000011, 0.625000] [ INFO] [1565073330.001004282]: : [35.000019, 0.584000] [ INFO] [1565073330.001031289]: : [36.000015, 0.559000] [ INFO] [1565073330.001063125]: : [37.000008, 0.536000] [ INFO] [1565073330.001090748]: : [38.000015, 0.522000] [ INFO] [1565073330.001118148]: : [39.000011, 0.516000] [ INFO] [1565073330.001145452]: : [40.000019, 0.506000] [ INFO] [1565073330.001172523]: : [41.000015, 0.507000] [ INFO] [1565073330.001199566]: : [42.000023, 0.505000] [ INFO] [1565073330.001226498]: : [43.000015, 0.508000] [ INFO] [1565073330.001253394]: : [44.000011, 0.521000] [ INFO] [1565073330.001280513]: : [45.000019, 0.534000] [ INFO] [1565073330.001314118]: : [46.000011, 0.638000] [ INFO] [1565073330.001341516]: : [47.000019, 0.641000] [ INFO] [1565073330.001368561]: : [48.000015, 0.653000] [ INFO] [1565073330.001395805]: : [49.000008, 0.660000] [ INFO] [1565073330.001422771]: : [50.000019, 0.658000] [ INFO] [1565073330.001449742]: : [51.000027, 0.642000] [ INFO] [1565073330.001481637]: : [52.000019, 0.734000] [ INFO] [1565073330.001508867]: : [53.000015, 0.711000] [ INFO] [1565073330.001538625]: : [54.000008, 0.706000] [ INFO] [1565073330.001568630]: : [55.000004, 0.701000] [ INFO] [1565073330.001598226]: : [56.000023, 0.718000] [ INFO] [1565073330.001625506]: : [57.000019, 0.787000] [ INFO] [1565073330.001653128]: : [58.000011, 0.787000] [ INFO] [1565073330.001680215]: : [59.000008, 0.814000] [ INFO] [1565073330.001713350]: : [60.000000, 0.826000] [ INFO] [1565073330.001741170]: : [61.000023, inf] [ INFO] [1565073330.001767770]: : [62.000019, inf] [ INFO] [1565073330.001794101]: : [63.000011, inf] [ INFO] [1565073330.001820764]: : [64.000008, 5.577000] [ INFO] [1565073330.001847892]: : [65.000031, 5.556000] [ INFO] [1565073330.001875504]: : [66.000023, 5.527000] [ INFO] [1565073330.001902723]: : [67.000015, 5.490000] [ INFO] [1565073330.001929200]: : [68.000008, 5.403000] [ INFO] [1565073330.001961932]: : [69.000008, 5.490000] [ INFO] [1565073330.001989064]: : [70.000031, 5.439000] [ INFO] [1565073330.002015865]: : [71.000023, 5.295000] [ INFO] [1565073330.002301451]: : [72.000015, 5.436000] [ INFO] [1565073330.002594452]: : [73.000008, 5.436000] [ INFO] [1565073330.002632882]: : [74.000008, 5.447000] [ INFO] [1565073330.002667886]: : [75.000023, inf] [ INFO] [1565073330.002697494]: : [76.000023, 1.168000] [ INFO] [1565073330.002731612]: : [77.000015, 1.173000] [ INFO] [1565073330.002763720]: : [78.000008, 1.175000] [ INFO] [1565073330.002797434]: : [79.000000, 1.173000] [ INFO] [1565073330.002830190]: : [80.000023, 1.175000] [ INFO] [1565073330.002863053]: : [81.000023, 1.176000] [ INFO] [1565073330.002894866]: : [82.000015, 1.178000] [ INFO] [1565073330.002922576]: : [83.000008, 1.180000] [ INFO] [1565073330.002949539]: : [84.000000, 1.181000] [ INFO] [1565073330.002977285]: : [85.000023, 1.180000] [ INFO] [1565073330.003005986]: : [86.000015, 1.183000] [ INFO] [1565073330.003033284]: : [87.000015, 1.194000] [ INFO] [1565073330.003060307]: : [88.000008, 1.345000] [ INFO] [1565073330.003088669]: : [89.000000, 1.350000] [ INFO] [1565073330.003117284]: : [90.000023, 1.352000] [ INFO] [1565073330.003148870]: : [91.000015, 1.316000] [ INFO] [1565073330.003178708]: : [92.000015, 1.289000] [ INFO] [1565073330.003208215]: : [93.000008, 1.244000] [ INFO] [1565073330.003240928]: : [94.000031, 1.224000] [ INFO] [1565073330.003268026]: : [95.000023, 1.227000] [ INFO] [1565073330.003297167]: : [96.000015, 1.244000] [ INFO] [1565073330.003369641]: : [97.000008, 1.385000] [ INFO] [1565073330.003406010]: : [98.000008, 1.626000] [ INFO] [1565073330.003437679]: : [99.000023, 1.592000] [ INFO] [1565073330.003468490]: : [100.000023, inf] [ INFO] [1565073330.003524483]: : [101.000015, inf] [ INFO] [1565073330.003929459]: : [102.000008, inf] [ INFO] [1565073330.004658947]: : [103.000008, inf] [ INFO] [1565073330.004719631]: : [104.000023, inf] [ INFO] [1565073330.004750077]: : [105.000023, inf] [ INFO] [1565073330.004780078]: : [106.000015, inf] [ INFO] [1565073330.004813317]: : [107.000008, inf] [ INFO] [1565073330.004842544]: : [108.000000, inf] [ INFO] [1565073330.004874080]: : [109.000023, inf] [ INFO] [1565073330.004905978]: : [110.000015, inf] [ INFO] [1565073330.004935609]: : [111.000015, inf] [ INFO] [1565073330.004967537]: : [112.000008, inf] [ INFO] [1565073330.004997547]: : [113.000000, inf] [ INFO] [1565073330.005029744]: : [114.000023, inf] [ INFO] [1565073330.005059137]: : [115.000015, inf] [ INFO] [1565073330.005091567]: : [116.000015, inf] [ INFO] [1565073330.005120646]: : [117.000008, inf] [ INFO] [1565073330.005155194]: : [118.000000, inf] [ INFO] [1565073330.005184733]: : [119.000023, inf] [ INFO] [1565073330.005216801]: : [120.000015, inf] [ INFO] [1565073330.005248435]: : [121.000008, inf] [ INFO] [1565073330.005281245]: : [122.000008, inf] [ INFO] [1565073330.005312482]: : [123.000031, inf] [ INFO] [1565073330.005344712]: : [124.000023, inf] [ INFO] [1565073330.005379831]: : [125.000015, inf] [ INFO] [1565073330.005409386]: : [126.000008, inf] [ INFO] [1565073330.005440584]: : [127.000008, inf] [ INFO] [1565073330.005471908]: : [128.000031, inf] [ INFO] [1565073330.005503980]: : [129.000015, inf] [ INFO] [1565073330.005546349]: : [130.000015, inf] [ INFO] [1565073330.005575459]: : [131.000015, inf] [ INFO] [1565073330.005606442]: : [132.000000, inf] [ INFO] [1565073330.005640792]: : [133.000031, inf] [ INFO] [1565073330.005671273]: : [134.000015, inf] [ INFO] [1565073330.005715494]: : [135.000015, inf] [ INFO] [1565073330.005751365]: : [136.000015, inf] [ INFO] [1565073330.005781186]: : [137.000000, inf] [ INFO] [1565073330.005866602]: : [138.000031, inf] [ INFO] [1565073330.005903243]: : [139.000015, inf] [ INFO] [1565073330.005938940]: : [140.000015, 0.350000] [ INFO] [1565073330.005971846]: : [141.000000, inf] [ INFO] [1565073330.006001783]: : [142.000000, 0.468000] [ INFO] [1565073330.006035195]: : [143.000031, inf] [ INFO] [1565073330.006067575]: : [144.000015, 0.536000] [ INFO] [1565073330.006101496]: : [145.000015, 0.533000] [ INFO] [1565073330.006131185]: : [146.000000, 0.528000] [ INFO] [1565073330.006166505]: : [147.000000, 0.524000] [ INFO] [1565073330.006195746]: : [148.000015, inf] [ INFO] [1565073330.006230134]: : [149.000015, 0.425000] [ INFO] [1565073330.006259691]: : [150.000015, inf] [ INFO] [1565073330.006294222]: : [151.000000, 0.512000] [ INFO] [1565073330.006323804]: : [152.000031, 0.507000] [ INFO] [1565073330.006357522]: : [153.000015, 0.504000] [ INFO] [1565073330.006389881]: : [154.000015, 0.501000] [ INFO] [1565073330.006423138]: : [155.000015, 0.500000] [ INFO] [1565073330.006453441]: : [156.000000, 0.497000] [ INFO] [1565073330.006486417]: : [157.000031, 0.495000] [ INFO] [1565073330.006518202]: : [158.000015, 0.494000] [ INFO] [1565073330.006550516]: : [159.000015, 0.435000] [ INFO] [1565073330.006581606]: : [160.000015, 0.432000] [ INFO] [1565073330.006613686]: : [161.000000, 0.506000] [ INFO] [1565073330.006644829]: : [162.000031, 0.503000] [ INFO] [1565073330.006691713]: : [163.000015, 0.502000] [ INFO] [1565073330.006727490]: : [164.000015, 0.500000] [ INFO] [1565073330.006758365]: : [165.000015, 0.500000] [ INFO] [1565073330.006792202]: : [166.000000, 0.499000] [ INFO] [1565073330.006824035]: : [167.000031, 0.499000] [ INFO] [1565073330.006857039]: : [168.000015, 0.499000] [ INFO] [1565073330.006888016]: : [169.000015, 0.499000] [ INFO] [1565073330.006920824]: : [170.000000, 0.498000] [ INFO] [1565073330.006953258]: : [171.000000, 0.499000] [ INFO] [1565073330.007243958]: : [172.000031, 0.499000] [ INFO] [1565073330.007279677]: : [173.000015, 0.501000] [ INFO] [1565073330.007313210]: : [174.000015, 0.501000] [ INFO] [1565073330.007342040]: : [175.000000, 0.502000] [ INFO] [1565073330.007370067]: : [176.000000, 0.503000] [ INFO] [1565073330.007398603]: : [177.000015, 0.504000] [ INFO] [1565073330.007434293]: : [178.000015, 0.505000] [ INFO] [1565073330.007463328]: : [179.000015, 0.507000] [ INFO] [1565073330.123775530]: I heard a laser scan laser[359]: [ INFO] [1565073330.123900333]: angle_range, -178.999983, 180.000005 [ INFO] [1565073330.123976601]: : [-178.999985, 0.512000] [ INFO] [1565073330.124052538]: : [-177.999985, 0.514000] [ INFO] [1565073330.124123003]: : [-176.999985, 0.517000] [ INFO] [1565073330.124197962]: : [-175.999985, 0.518000] [ INFO] [1565073330.124307041]: : [-174.999985, 0.523000]
トピックscanを表示します。
rostopic echo /scan
起動時の画面
header: seq: 722 stamp: secs: 1565073413 nsecs: 232595190 frame_id: "base_scan" angle_min: -3.12413907051 angle_max: 3.14159274101 angle_increment: 0.0174532923847 time_increment: 0.00039700823254 scan_time: 0.142525956035 range_min: 0.15000000596 range_max: 12.0 ranges: [0.5120000243186951, 0.5130000114440918, 0.515999972820282, 0.5189999938011169, 0.5210000276565552, 0.5239999890327454, 0.5270000100135803, 0.5289999842643738, 0.5329999923706055, 0.5360000133514404, 0.5410000085830688, 0.5460000038146973, 0.5490000247955322, 0.5550000071525574, 0.5580000281333923, 0.5640000104904175, 0.5680000185966492, 0.5759999752044678, 0.5799999833106995, 0.5870000123977661, 0.5910000205039978, 0.6000000238418579, 0.609000027179718, 0.6140000224113464, 0.6190000176429749, 0.6299999952316284, 0.6430000066757202, 0.6480000019073486, 0.652999997138977, 0.6660000085830688, 0.6809999942779541, 0.6869999766349792, 0.7039999961853027, 0.7129999995231628, 0.7269999980926514, 0.7379999756813049, 0.7559999823570251, 0.47099998593330383, 0.4650000035762787, 0.460999995470047, 0.4580000042915344, inf, inf, inf, inf, 0.3889999985694885, 0.3919999897480011, inf, inf, inf, inf, inf, 0.9399999976158142, 0.9399999976158142, 0.9300000071525574, 0.9259999990463257, 0.9739999771118164, 1.003000020980835, 1.50600004196167, 1.5379999876022339, 1.5829999446868896, inf, inf, inf, 1.9550000429153442, inf, inf, 3.9809999465942383, 2.765000104904175, 2.828000068664551, 3.3970000743865967, 2.8480000495910645, 3.1010000705718994, 3.117000102996826, 2.8450000286102295, 2.8450000286102295, 2.8429999351501465, 2.8440001010894775, 2.8559999465942383, 2.8499999046325684, 2.864000082015991, 2.8550000190734863, 3.365999937057495, 3.368000030517578, 3.368000030517578, 3.380000114440918, 3.384999990463257, 3.390000104904175, 3.4110000133514404, 3.443000078201294, 3.434000015258789, 2.950000047683716, 2.881999969482422, 2.8910000324249268, 2.9049999713897705, 2.9210000038146973, 2.9260001182556152, 2.9489998817443848, 2.9690001010894775, 2.9839999675750732, 3.6089999675750732, 3.624000072479248, 3.6519999504089355, 3.6600000858306885, 3.569999933242798, 3.73799991607666, 3.7339999675750732, 3.802999973297119, 3.819000005722046, 3.5399999618530273, 3.700000047683716, 3.7699999809265137, 3.763000011444092, 3.750999927520752, inf, inf, inf, inf, inf, inf, inf, inf, 3.50600004196167, 3.5369999408721924, 3.61299991607666, 3.6700000762939453, inf, 3.25, 3.2920000553131104, inf, inf, inf, 2.9820001125335693, 2.9700000286102295, 3.0409998893737793, 3.1510000228881836, 3.265000104904175, 3.321000099182129, 3.427000045776367, 2.803999900817871, 2.8580000400543213, 2.8970000743865967, 3.0179998874664307, 3.1570000648498535, 3.194999933242798, 2.9040000438690186, 2.9790000915527344, 3.1449999809265137, 3.50600004196167, 3.490999937057495, 3.4679999351501465, 3.4549999237060547, 3.1760001182556152, 3.1659998893737793, 3.2330000400543213, 3.36899995803833, 3.364000082015991, 3.3440001010894775, 3.3369998931884766, 3.3310000896453857, 3.3269999027252197, 3.3259999752044678, 3.305999994277954, 3.2950000762939453, 3.2669999599456787, 3.2829999923706055, 3.2820000648498535, 3.2769999504089355, 3.257999897003174, 3.256999969482422, 3.2799999713897705, 3.263000011444092, 3.26200008392334, 3.263000011444092, 3.302999973297119, 3.2980000972747803, 3.302999973297119, 3.325000047683716, 3.3239998817443848, 3.3410000801086426, 3.3410000801086426, 3.3489999771118164, 3.2780001163482666, 3.3929998874664307, 3.378999948501587, 3.4059998989105225, 3.440000057220459, 3.453000068664551, 3.4800000190734863, 3.4830000400543213, inf, 3.443000078201294, 3.0299999713897705, 3.063999891281128, 3.431999921798706, inf, 0.9020000100135803, 0.890999972820282, 0.902999997138977, 0.9129999876022339, 0.9240000247955322, 0.9459999799728394, 0.9710000157356262, 0.9819999933242798, 1.0080000162124634, 1.0199999809265137, 1.0420000553131104, 1.0529999732971191, 1.0770000219345093, 1.090999960899353, 1.1169999837875366, 1.13100004196167, 1.1579999923706055, inf, 0.7080000042915344, 0.6520000100135803, 0.6309999823570251, 0.6039999723434448, 0.5740000009536743, 0.5649999976158142, 0.5519999861717224, 0.5479999780654907, 0.5410000085830688, 0.5410000085830688, 0.5440000295639038, 0.5619999766349792, 0.5839999914169312, 0.7099999785423279, 0.7260000109672546, 0.734000027179718, 0.7179999947547913, 0.7110000252723694, 0.796999990940094, 0.8009999990463257, inf, 5.715000152587891, 5.510000228881836, 5.624000072479248, inf, inf, inf, inf, inf, 5.561999797821045, 5.539000034332275, 5.519000053405762, 5.400000095367432, 5.3460001945495605, 5.484000205993652, 5.4730000495910645, 5.263000011444092, 5.234000205993652, 5.459000110626221, 5.459000110626221, inf, 1.1710000038146973, 1.1829999685287476, 1.1890000104904175, 1.2519999742507935, 1.2389999628067017, 1.184999942779541, 1.1759999990463257, 1.1799999475479126, 1.1790000200271606, 1.1829999685287476, 1.1890000104904175, 1.1929999589920044, 1.3509999513626099, 1.347000002861023, 1.3509999513626099, 1.3609999418258667, 1.3569999933242798, 1.2259999513626099, 1.218000054359436, 1.2259999513626099, 1.2319999933242798, 1.2369999885559082, 1.6160000562667847, 1.5880000591278076, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, inf, 0.35199999809265137, inf, inf, 0.4560000002384186, 0.5410000085830688, 0.5339999794960022, 0.5289999842643738, inf, 0.4230000078678131, 0.4269999861717224, 0.5120000243186951, 0.5099999904632568, 0.5059999823570251, 0.5040000081062317, 0.5009999871253967, 0.5009999871253967, 0.4970000088214874, 0.4950000047683716, 0.49300000071525574, 0.42899999022483826, 0.4309999942779541, inf, 0.5070000290870667, 0.5009999871253967, 0.49900001287460327, 0.5, 0.49900001287460327, 0.49900001287460327, 0.49799999594688416, 0.49900001287460327, 0.49900001287460327, 0.5, 0.5, 0.5, 0.5009999871253967, 0.5019999742507935, 0.503000020980835, 0.503000020980835, 0.5059999823570251, 0.5070000290870667, 0.5099999904632568] intensities: [47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 0.0, 0.0, 0.0, 47.0, 47.0, 0.0, 0.0, 0.0, 0.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 0.0, 0.0, 47.0, 0.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 47.0, 47.0, 47.0, 47.0, 0.0, 47.0, 47.0, 0.0, 0.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 47.0, 47.0, 47.0, 47.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 47.0, 47.0, 47.0, 0.0, 0.0, 0.0, 0.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 47.0, 0.0, 0.0, 47.0, 47.0, 47.0, 47.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 0.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0, 47.0] --- header: seq: 723 stamp: secs: 1565073413 nsecs: 376067591 frame_id: "base_scan" angle_min: -3.12413907051 angle_max: 3.14159274101 angle_increment: 0.0174532923847 time_increment: 0.000375517789507 scan_time: 0.134810894728 range_min: 0.15000000596 range_max: 12.0 ranges: [0.5109999775886536, 0.5130000114440918, 0.515999972820282, 0.5189999938011169, 0.5210000276565552, 0.5239999890327454, 0.5260000228881836, 0.531000018119812, 0.5329999923706055,
ROSのノードとトピックを表示します。
rqt_graph
ROSの座標変換TFを表示します。
rosrun tf view_frames
または
rosrun rqt_tf_tree rqt_tf_tree