空飛ぶロボットのつくりかた

ロボットをつくるために必要な技術をまとめます。ロボットの未来についても考えたりします。

デジタル画像撮影のお勉強(1)

やりたいこと

デジタル画像撮影について学ぶ

教科書

CG-ARTS | 書籍・教材

カメラの構成要素

f:id:robonchu:20180407110137p:plain

画像生成の幾何学モデル

ピンホールカメラモデル

f:id:robonchu:20180407110951p:plain

  • レンズを使うと明るくなるがピント合わせが必要

  • ピンホールカメラはピント合わせが不要

参考:

透視投影モデル

f:id:robonchu:20180407112022p:plain

参考:

レンズモデル

薄肉レンズ

f:id:robonchu:20180407113056j:plain

参考:

厚肉レンズ

f:id:robonchu:20180407113430j:plain

参考:

歪曲収差

f:id:robonchu:20180407223630j:plain

参考:

周辺光量の低下

f:id:robonchu:20180407224114g:plain

参考:

撮影パラメータ

撮影画角

f:id:robonchu:20180407224809j:plain

参考:

撮像素子サイズ

f:id:robonchu:20180407225658p:plain

CMOSとCCD

f:id:robonchu:20180407225338g:plain

参考:

レンズ焦点距離

35mm換算焦点距離

f:id:robonchu:20180407230204p:plain

標準・広角・望遠レンズ

f:id:robonchu:20180407230113j:plain

カニカルシャッター

f:id:robonchu:20180407230837j:plain

ミラー機構

f:id:robonchu:20180407231046j:plain

参考:

画像の明るさ

T・B・D

カラー画像

加法混色と減法混色

可視光

f:id:robonchu:20180408212911j:plain

人間の視覚

f:id:robonchu:20180408213203j:plain

加法混色

f:id:robonchu:20180408213305p:plain

減法混色

f:id:robonchu:20180408213534p:plain

参考:

カラー画像の撮影

3板式

3板式

f:id:robonchu:20180408213957g:plain

単板式

f:id:robonchu:20180408214745p:plain

バイリニア補間

f:id:robonchu:20180408215216p:plain

エッジセンシング補間 : T・B・D

参考:

主成分分析のお勉強

やりたいこと

三次元点群に最もフィットする主軸を導出したい!

教科書

実装コード

#coding:utf-8
import numpy
from sklearn.decomposition import PCA

N = 20
t = numpy.random.rand(N)
x = t+numpy.random.rand(N)*0.3
y = t+numpy.random.rand(N)*0.3
z = t+numpy.random.rand(N)*0.3

pca_o = PCA(n_components=3)
pca_o.fit(zip(x,y,z))
pca = pca_o.components_

v  = []
mx = numpy.mean(x)
my = numpy.mean(y)
mz = numpy.mean(z)

for tx,ty,tz in zip(x,y,z):
    ax,ay,az = numpy.dot(pca,[(tx-mx),(ty-my),(tz-mz)])
    v.append( dict(ax=ax,ay=ay,az=az,x=tx,y=ty,z=tz) )

maxx = max(v,key=lambda x:x['ax'])
minx = min(v,key=lambda x:x['ax'])
maxy = max(v,key=lambda x:x['ay'])
miny = min(v,key=lambda x:x['ay'])
maxz = max(v,key=lambda x:x['az'])
minz = min(v,key=lambda x:x['az'])

#グラフ描画
from matplotlib.pyplot import *
from mpl_toolkits.mplot3d import Axes3D

fig = figure()
ax = Axes3D(fig)
ax.scatter3D(x,y,z)

# 表示範囲の設定
ax.set_xlim(0, 1.5)
ax.set_ylim(0, 1.5)
ax.set_zlim(0, 1.5)

#基底ベクトルの描画
v1x,v1y,v1z = pca[0]
ax.plot([mx+v1x,mx-v1x],[my+v1y,my-v1y],[mz+v1z,mz-v1z])
v2x,v2y,v2z = pca[1]
ax.plot([mx+v2x,mx-v2x],[my+v2y,my-v2y],[mz+v2z,mz-v2z])
v3x,v3y,v3z = pca[2]
ax.plot([mx+v3x,mx-v3x],[my+v3y,my-v3y],[mz+v3z,mz-v3z])

ax.plot([maxx['x']], [maxx['y']], [maxx['z']], "*", color="b", ms=10, mew=0.5)
ax.plot([minx['x']], [minx['y']], [minx['z']], "*", color="b", ms=10, mew=0.5)
ax.plot([maxy['x']], [maxy['y']], [maxy['z']], "*", color="r", ms=10, mew=0.5)
ax.plot([miny['x']], [miny['y']], [miny['z']], "*", color="r", ms=10, mew=0.5)
ax.plot([maxz['x']], [maxz['y']], [maxz['z']], "*", color="g", ms=10, mew=0.5)
ax.plot([minz['x']], [minz['y']], [minz['z']], "*", color="g", ms=10, mew=0.5)

show()

f:id:robonchu:20180401195542p:plain

ブルーの線が主軸です!

☆がそれぞれの軸での最大・最小の点!!

これを使って何をするかはお楽しみ♪

NeoPixel Ringで遊んでみる

やりたいこと

Neo Pixcel の LEDをいい感じに光らせたい💡

f:id:robonchu:20180325215325j:plain

購入したNeo Pixcel LED

780円〜♪

https://www.amazon.co.jp/waves-NeoPixel-%E3%83%8D%E3%82%AA%E3%83%94%E3%82%AF%E3%82%BB%E3%83%AB-WS2812B-24%E5%80%8B/dp/B07926DQWQ

教科書

https://learn.adafruit.com/florabrella/test-the-neopixel-strip

ハンダ付け

👇こんな感じ

f:id:robonchu:20180325214712j:plain

配線

  • VCC -> 5V

  • GND -> GND

  • IN -> 6番pin

下記写真参考

Arduinoの設定

robonchu.hatenablog.com

NeoPixelのライブラリ設定

  1. GitHub - adafruit/Adafruit_NeoPixel: Neo Pixels!からクローン

  2. クローンしてきたディレクトリを~/arduino-1.8.5/libraries/NeoPixelに配置

スケッチ

#include <Adafruit_NeoPixel.h>

#define PIN 6

// Parameter 1 = number of pixels in strip
// Parameter 2 = pin number (most are valid)
// Parameter 3 = pixel type flags, add together as needed:
//   NEO_KHZ800  800 KHz bitstream (most NeoPixel products w/WS2812 LEDs)
//   NEO_KHZ400  400 KHz (classic 'v1' (not v2) FLORA pixels, WS2811 drivers)
//   NEO_GRB     Pixels are wired for GRB bitstream (most NeoPixel products)
//   NEO_RGB     Pixels are wired for RGB bitstream (v1 FLORA pixels, not v2)
Adafruit_NeoPixel strip = Adafruit_NeoPixel(160, PIN, NEO_GRB + NEO_KHZ800);

void setup() {
  strip.begin();
  strip.setBrightness(30); //adjust brightness here
  strip.show(); // Initialize all pixels to 'off'
}

void loop() {
  // Some example procedures showing how to display to the pixels:
  colorWipe(strip.Color(255, 0, 0), 50); // Red
  colorWipe(strip.Color(0, 255, 0), 50); // Green
  colorWipe(strip.Color(0, 0, 255), 50); // Blue
  rainbow(20);
  rainbowCycle(20);
}

// Fill the dots one after the other with a color
void colorWipe(uint32_t c, uint8_t wait) {
  for(uint16_t i=0; i<strip.numPixels(); i++) {
      strip.setPixelColor(i, c);
      strip.show();
      delay(wait);
  }
}

void rainbow(uint8_t wait) {
  uint16_t i, j;

  for(j=0; j<256; j++) {
    for(i=0; i<strip.numPixels(); i++) {
      strip.setPixelColor(i, Wheel((i+j) & 255));
    }
    strip.show();
    delay(wait);
  }
}

// Slightly different, this makes the rainbow equally distributed throughout
void rainbowCycle(uint8_t wait) {
  uint16_t i, j;

  for(j=0; j<256*5; j++) { // 5 cycles of all colors on wheel
    for(i=0; i< strip.numPixels(); i++) {
      strip.setPixelColor(i, Wheel(((i * 256 / strip.numPixels()) + j) & 255));
    }
    strip.show();
    delay(wait);
  }
}

// Input a value 0 to 255 to get a color value.
// The colours are a transition r - g - b - back to r.
uint32_t Wheel(byte WheelPos) {
  if(WheelPos < 85) {
   return strip.Color(WheelPos * 3, 255 - WheelPos * 3, 0);
  } else if(WheelPos < 170) {
   WheelPos -= 85;
   return strip.Color(255 - WheelPos * 3, 0, WheelPos * 3);
  } else {
   WheelPos -= 170;
   return strip.Color(0, WheelPos * 3, 255 - WheelPos * 3);
  }
}

これを書き込めばOK💡

f:id:robonchu:20180325215217j:plain

RasPiでトライ

参考:

所感

とても綺麗✨

色んな光らせ方を考えていきたいな〜

参考

Visual Studio CodeでROSプログラミング

やりたいこと

統合開発環境でROSプログラミング

f:id:robonchu:20180320235908p:plain

Visual Studio Code

参考:

C++

拡張機能の追加

C++で検索し、一番上をインストール後、再読み込み

Hello World

#include <iostream>

int main()
{
    std::cout << "Hello, World" << std::endl;
}

taskの作成

  • Ctrl + Shift + p

  • Configure Task

  • tasks.json

{
    // See https://go.microsoft.com/fwlink/?LinkId=733558
    // for the documentation about the tasks.json format
    "version": "2.0.0",
    "tasks": [
        {
            "label": "build",
            "type": "shell",
            "command": "g++",
            "args": ["-O2", "-g", "test.cpp"],
        }
    ]
}

build

  • Ctrl + Shift + b

  • build

これでa.outができているはず

ROS

拡張機能の追加

ROSで検索し、一番上をインストール後、再読み込み

Create Package

  • Ctrl + Shift + p

  • ROS

  • Create Catkin Package

  • roscpp std_msgs

f:id:robonchu:20180320235834p:plain

Emacs 設定

Raspberry Pi Zero W で遊んでみる(1)~IP CAMERA~

やりたいこと

raspberry pi zero w でIPカメラを作る

IPカメラを作ってみる

Bluetoothで接続

Raspberry Pi Zero WでBluetooth経由でシリアル通信(ペアリングまで) - 極力ローコスト ロボット製作 ブログ

カメラの接続

f:id:robonchu:20180319191612p:plain

データの送受信

いろんな方法がある

  1. picameraのチュートリアルに"Capturing to a network stream"という項があり、socket通信で画像をストリーミングしている

  2. opencvでも可能

  3. mjpg-streamerでstreaming

参考

raspiから映像をストリーミング

raspi側: mjpg-streamerでstreaming

参考: 5GHz WiFi対応させたPi Zero rev1.3とPi Cameraでミニマムなネットワークカメラを作ってみた(mjpg-streamer版) | きっと何かに役立つでしょ!?

上記通りにして、webブラウザに http://192.168.xx.xx:9000を打ち込むと以下のように表示される

f:id:robonchu:20180319193059p:plain

おまけ:OpenCVのインストール

$ sudo apt-get install python-opencv
PC側

参考: PythonとOpenCV3でストリーミング映像をキャプチャする方法 - Live the Life you Love

#!/usr/bin/env python
# -*- coding: utf-8 -*-

import cv2

URL = "http://raspberry.local:8081/?action=stream"
s_video = cv2.VideoCapture(URL)

while True:
  ret, img = s_video.read()
  cv2.imshow("Stream Video",img)
  key = cv2.waitKey(1) & 0xff
  if key == ord('q'): break

f:id:robonchu:20180319194334p:plain

所感

f:id:robonchu:20180319195157j:plain

めっちゃコンパクト! 遅延もそこまでない、いい感じ♪

ってかraspi zeroにros入るのかな...調べてみよう

参考HP

raspi関連商品

PCLを使って遊んでみる

やりたいこと

点群情報の処理をうまく扱えるようになりたい

f:id:robonchu:20180304194956p:plain

教科書

Point Cloud Dataの作成

Documentation - Point Cloud Library (PCL)

実行手順(以下のスクリプトを同じ階層に準備した前提)

  1. mkdir build

  2. cd build

  3. cmake ..

  4. make

  5. ./pcd_write_test

pcdの型

width, height, points.sizeの要素が必要で、あとはこのpointsにxyzのデータをつめる

  pcl::PointCloud<pcl::PointXYZ> cloud;

  // Fill in the cloud data
  cloud.width    = 5;
  cloud.height   = 1;
  cloud.is_dense = false;
  cloud.points.resize (cloud.width * cloud.height);

実装

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>

int
  main (int argc, char** argv)
{
  pcl::PointCloud<pcl::PointXYZ> cloud;

  // Fill in the cloud data
  cloud.width    = 5;
  cloud.height   = 1;
  cloud.is_dense = false;
  cloud.points.resize (cloud.width * cloud.height);

  for (size_t i = 0; i < cloud.points.size (); ++i)
  {
    cloud.points[i].x = 1024 * rand () / (RAND_MAX + 1.0f);
    cloud.points[i].y = 1024 * rand () / (RAND_MAX + 1.0f);
    cloud.points[i].z = 1024 * rand () / (RAND_MAX + 1.0f);
  }

  pcl::io::savePCDFileASCII ("test_pcd.pcd", cloud);
  std::cerr << "Saved " << cloud.points.size () << " data points to test_pcd.pcd." << std::endl;

  for (size_t i = 0; i < cloud.points.size (); ++i)
    std::cerr << "    " << cloud.points[i].x << " " << cloud.points[i].y << " " << cloud.points[i].z << std::endl;

  return (0);
}

結果

Saved 5 data points to test_pcd.pcd.
    0.352222 -0.151883 -0.106395
    -0.397406 -0.473106 0.292602
    -0.731898 0.667105 0.441304
    -0.734766 0.854581 -0.0361733
    -0.4607 -0.277468 -0.916762

CMakeLists.txt

cmake_minimum_required(VERSION 2.6 FATAL_ERROR)
project(MY_GRAND_PROJECT)
find_package(PCL 1.3 REQUIRED COMPONENTS common io)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})
add_executable(pcd_write_test pcd_write.cpp)
target_link_libraries(pcd_write_test ${PCL_COMMON_LIBRARIES} ${PCL_IO_LIBRARIES})

平面検出

Documentation - Point Cloud Library (PCL)

重要な部分

  • seg.setDistanceThreshold (0.01);

    • このパラメータどれくらい分厚いものを平面と分類するかが変わる。

    • softkineticでは平面の点群が分厚くなる傾向にあるため0.03~0.04に設定すると良い

  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
  // Create the segmentation object
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  // Optional
  seg.setOptimizeCoefficients (true);
  // Mandatory
  seg.setModelType (pcl::SACMODEL_PLANE);
  seg.setMethodType (pcl::SAC_RANSAC);
  seg.setDistanceThreshold (0.01);

  seg.setInputCloud (cloud);
  seg.segment (*inliers, *coefficients);

実装

#include <iostream>
#include <pcl/ModelCoefficients.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>

int
 main (int argc, char** argv)
{
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);

  // Fill in the cloud data
  cloud->width  = 15;
  cloud->height = 1;
  cloud->points.resize (cloud->width * cloud->height);

  // Generate the data
  for (size_t i = 0; i < cloud->points.size (); ++i)
  {
    cloud->points[i].x = 1024 * rand () / (RAND_MAX + 1.0f);
    cloud->points[i].y = 1024 * rand () / (RAND_MAX + 1.0f);
    cloud->points[i].z = 1.0;
  }

  // Set a few outliers
  cloud->points[0].z = 2.0;
  cloud->points[3].z = -2.0;
  cloud->points[6].z = 4.0;

  std::cerr << "Point cloud data: " << cloud->points.size () << " points" << std::endl;
  for (size_t i = 0; i < cloud->points.size (); ++i)
    std::cerr << "    " << cloud->points[i].x << " "
                        << cloud->points[i].y << " "
                        << cloud->points[i].z << std::endl;

  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
  // Create the segmentation object
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  // Optional
  seg.setOptimizeCoefficients (true);
  // Mandatory
  seg.setModelType (pcl::SACMODEL_PLANE);
  seg.setMethodType (pcl::SAC_RANSAC);
  seg.setDistanceThreshold (0.01);

  seg.setInputCloud (cloud);
  seg.segment (*inliers, *coefficients);

  if (inliers->indices.size () == 0)
  {
    PCL_ERROR ("Could not estimate a planar model for the given dataset.");
    return (-1);
  }

  std::cerr << "Model coefficients: " << coefficients->values[0] << " " 
                                      << coefficients->values[1] << " "
                                      << coefficients->values[2] << " " 
                                      << coefficients->values[3] << std::endl;

  std::cerr << "Model inliers: " << inliers->indices.size () << std::endl;
  for (size_t i = 0; i < inliers->indices.size (); ++i)
    std::cerr << inliers->indices[i] << "    " << cloud->points[inliers->indices[i]].x << " "
                                               << cloud->points[inliers->indices[i]].y << " "
                                               << cloud->points[inliers->indices[i]].z << std::endl;

  return (0);
}
CMakeLists.txt
cmake_minimum_required(VERSION 2.8 FATAL_ERROR)

project(planar_segmentation)

find_package(PCL 1.2 REQUIRED)

include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})

add_executable (planar_segmentation planar_segmentation.cpp)
target_link_libraries (planar_segmentation ${PCL_LIBRARIES})

ROS x PCLで平面検出

softkineticの点群データを受け取って平面検出を行う

├── CMakeLists.txt
├── package.xml
└── src
    └── planar_segmentation.cpp

実装

  • seg.setDistanceThreshold (0.01) -> (0.04);に修正
#include <string>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl_msgs/ModelCoefficients.h>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>

class PlaneSegmentation {
 public:
  PlaneSegmentation()
      : segmentation_cloud_(new pcl::PointCloud<pcl::PointXYZRGB>) {
    std::string topic_name = "/softkinetic_camera/depth/points";
    cloud_sub_ = nh_.subscribe(topic_name, 1, &PlaneSegmentation::SegmentationCb, this);

    if (!ros::topic::waitForMessage<sensor_msgs::PointCloud2>(topic_name, ros::Duration(10.0))) {
      ROS_ERROR("timeout");
      exit(EXIT_FAILURE);
    }

    plane_pub_ = nh_.advertise<sensor_msgs::PointCloud2>("/plane_segmentation", 1);
  }

  pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr GetSegmentationCloud() const {
    return PlaneSegmentation::segmentation_cloud_;
  }

 private:
  ros::NodeHandle nh_;
  ros::Subscriber cloud_sub_;
  ros::Publisher plane_pub_;
  pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmentation_cloud_;

  void SegmentationCb(const sensor_msgs::PointCloud2ConstPtr& msg) {
    pcl::PointCloud<pcl::PointXYZRGB> cloud;
    pcl::fromROSMsg(*msg, cloud);

    pcl::SACSegmentation<pcl::PointXYZRGB> seg;
    seg.setOptimizeCoefficients(true);
    seg.setModelType(pcl::SACMODEL_PLANE);
    seg.setMethodType(pcl::SAC_RANSAC);
    seg.setDistanceThreshold(0.04);
    seg.setInputCloud(cloud.makeShared());

    pcl::PointIndices inliers;
    pcl::ModelCoefficients coefficients;
    seg.segment(inliers, coefficients);

    pcl::copyPointCloud(cloud, *segmentation_cloud_);
    for (size_t i = 0; i < inliers.indices.size(); i++) {
      segmentation_cloud_->points[inliers.indices[i]].r = 255;
      segmentation_cloud_->points[inliers.indices[i]].g = 0;
      segmentation_cloud_->points[inliers.indices[i]].b = 0;
    }

    sensor_msgs::PointCloud2 pub_cloud;
    pcl::toROSMsg(*segmentation_cloud_, pub_cloud);
    plane_pub_.publish(pub_cloud);
  }
};

int main(int argc, char** argv) {
  ros::init(argc, argv, "plane_segmentation");
  PlaneSegmentation plane_segmentation;
  ros::Rate spin_rate(10);

  pcl::visualization::CloudViewer viewer("Viewer");

  while (ros::ok()) {
    ros::spinOnce();
    if (!viewer.wasStopped()) {
      viewer.showCloud(plane_segmentation.GetSegmentationCloud());
    }
    spin_rate.sleep();
  }

  return 0;
}

CMakeLists.txt

find_package(catkin REQUIRED COMPONENTS
  pcl_conversions
  pcl_ros
  roscpp
  sensor_msgs
)

catkin_package(
  CATKIN_DEPENDS
  roscpp
  sensor_msgs
)

include_directories(
  ${catkin_INCLUDE_DIRS}
)

add_executable(planar_segmentation src/planar_segmentation.cpp)

target_link_libraries(plane_detection
  ${catkin_LIBRARIES}

pacage.xml

  <buildtool_depend>catkin</buildtool_depend>

  <build_depend>pcl_conversions</build_depend>
  <build_depend>pcl_ros</build_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>sensor_msgs</build_depend>

  <run_depend>pcl_conversions</run_depend>
  <run_depend>pcl_ros</run_depend>
  <run_depend>roscpp</run_depend>
  <run_depend>sensor_msgs</run_depend>

結果

Tutorialと同様の結果がでていない気がする。何かおかしいかも。

帯みたいになってる。なんでだろう。。。

f:id:robonchu:20180304194956p:plain

参考

座標変換のお勉強

やりたいこと

  • ロボットの3次元座標の考え方を理解して、制御に役立てる

  • ROSのtfの理解

座標変換教科書

tf教科書

tfを簡単に体験する

  • roslaunch turtle_tf turtle_tf_demo.launch
  • rosnode list
    • node チェック
  • rosrun tf view_frames
    • tf チェック
  • rosrun tf tf_echo world turtle1
  • rosrun tf tf_echo turtle1 turtle2
    • 座標変換チェック

f:id:robonchu:20180304151903p:plain

tfの座標情報処理

ブロードキャスター

python

    br = tf.TransformBroadcaster()
    br.sendTransform((msg.x, msg.y, 0),
                     tf.transformations.quaternion_from_euler(0, 0, msg.theta),
                     rospy.Time.now(),
                     turtlename,
                     "world")

c++

  static tf::TransformBroadcaster br;
  tf::Transform transform;
  transform.setOrigin( tf::Vector3(msg->x, msg->y, 0.0) );
  tf::Quaternion q;
  q.setRPY(0, 0, msg->theta);
  transform.setRotation(q);
  br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "world", turtle_name));

リスナー

  • listener.lookupTransform('/turtle2', '/turtle1', rospy.Time(0))

  • /turtle2を/turtle1座標系に変換する

#!/usr/bin/env python  
import roslib
roslib.load_manifest('learning_tf')
import rospy
import math
import tf
import geometry_msgs.msg
import turtlesim.srv

if __name__ == '__main__':
    rospy.init_node('turtle_tf_listener')

    listener = tf.TransformListener()

    rospy.wait_for_service('spawn')
    spawner = rospy.ServiceProxy('spawn', turtlesim.srv.Spawn)
    spawner(4, 2, 0, 'turtle2')

    turtle_vel = rospy.Publisher('turtle2/cmd_vel', geometry_msgs.msg.Twist,queue_size=1)

    rate = rospy.Rate(10.0)
    while not rospy.is_shutdown():
        try:
            (trans,rot) = listener.lookupTransform('/turtle2', '/turtle1', rospy.Time(0))
        except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
            continue

        angular = 4 * math.atan2(trans[1], trans[0])
        linear = 0.5 * math.sqrt(trans[0] ** 2 + trans[1] ** 2)
        cmd = geometry_msgs.msg.Twist()
        cmd.linear.x = linear
        cmd.angular.z = angular
        turtle_vel.publish(cmd)

        rate.sleep()

フレームの追加

#!/usr/bin/env python  
import roslib
roslib.load_manifest('learning_tf')

import rospy
import tf
import math

if __name__ == '__main__':
    rospy.init_node('my_tf_broadcaster')
    br = tf.TransformBroadcaster()
    rate = rospy.Rate(10.0)
    while not rospy.is_shutdown():
        t = rospy.Time.now().to_sec() * math.pi
        br.sendTransform((2.0 * math.sin(t), 2.0 * math.cos(t), 0.0),
                         (0.0, 0.0, 0.0, 1.0),
                         rospy.Time.now(),
                         "carrot1",
                         "turtle1")
        rate.sleep()

過去のtfの時間を利用

        try:
            now = rospy.Time.now()
            past = now - rospy.Duration(5.0)
            listener.waitForTransformFull("/turtle2", now,
                                          "/turtle1", past,
                                          "/world", rospy.Duration(1.0))
            (trans, rot) = listener.lookupTransformFull("/turtle2", now,
                                                      "/turtle1", past,
                                                      "/world")

所感

tfまぁ便利。時間の考え方がわかったようなわからないような。。。

世界で一番簡単なtfの使い方 - MyEnigmaの記事から抜粋

  1. ros::time::now()を使ってLookupTransformしてはいけない。

tfはtf_broadcasterによって登録されたtf間の間の時間しか、座標変換できません。

ですのでros::time::now()で時間指定すると、座標変換できません。

つまり、基本的にtfは過去の時間を指定してLookupTransformする必要があります。

そんな時は下記のリンクの通り、tfが登録されるまで時間を待つようにすると、

きちんと座標変換してくれます。

ja/tf/Tutorials/tf and Time (C++) - ROS Wiki