Contents
TeleopPanel
概要
このチュートリアルはRViz用のシンプルなパネルの書き方について解説します。
RVizのパネルは、メインウインドウ内につけるか、フローティングできるGUIのウィジェットです。ディスプレイのように“Displays”パネルの中にプロパティを表示するのではなく、3Dのシーンの中で表示します。
パネルはアプリケーションに特化したGUIの要素をまとめて置く場所として役に立つ場所です。ロボットや他のコマンドや入力制御ためのスタート・ストップボタンを置くことができるでしょう。
RVizは、ゴール姿勢を経路探索に送るためのビルトインツールを持っていますが、それには、ロボットのベース・コントローラに速度司令を直接送る本来の方法がありません。これがこのチュートリアルで解説するのは、rviz::Panelのサブクラスで、速度司令を正しく自分のロボットに送るようにするというものです。
このチュートリアルのソースコードはrviz_plugin_tutorialsのパッケージ内にあります。ソースのディレクトリを確認、または(もしUbuntuを使っているなら)コンパイル済みのパッケージを、以下のようにapt-getでインストールできます:
sudo apt-get install ros-hydro-visualization-tutorials
新しい“Teleop”パネルによるRVizがどのようなものかというのが、この左側に示されています:
プラグインコード
TeleopPanelのコードはこれらのファイルにあります: src/teleop_panel.h, src/teleop_panel.cpp, src/drive_widget.h, src/drive_widget.cpp.
teleop_panel.h
teleop_panel.hの全内容は:src/teleop_panel.h.
ここでは、rviz::Panelの新しいサブクラスを宣言します。Panels/Add_New_Panelメニューを介して追加できる全てのパネルはrviz::Panelのサブクラスです。
TeleopPanelは、出力しているトピックと2D制御エリアをセットするテキスト入力欄を表示します。2D制御エリアはDriveWidgetクラスから実装され、かつそのクラスに記述されます。
class TeleopPanel: public rviz::Panel {
このクラスはQtスロットを使い、QObjectのサブクラスなので、Q_OBJECTマクロが必要です。
Q_OBJECT public:
QWidgetサブクラスのコンストラクタは、通常、親ウィジェットのパラメータ(通常デフォルトに0(ゼロ))を取ります。同時に、デフォルトコンストラクタからの呼び出し(引数なし)で呼ばれて、pluginlib::ClassLoaderがインスタンスを生成します。パラメータを取り、かつ0のデフォルト値を与えることでデフォルトコンストラクタは働き、同時に親ウィジェットの中で何か他のものを親ウィジェットに渡すためのクラスとしてどれかを使います。
TeleopPanel( QWidget* parent = 0 );
configファイルからのデータのロードとセーブのために、rviz::Panelの関数をオーバライドを宣言します。ここでのデータはトピックの名前です。
virtual void load( const rviz::Config& config ); virtual void save( rviz::Config config ) const;
次は一組のpublicのQtスロットです。
public Q_SLOTS:
制御エリアDriveWidgetは再利用を容易にするために、DriveWidgetの出力をQtシグナルに送るので、この出力を受け取るために、ここでQtスロットを宣言します。
void setVel( float linear_velocity_, float angular_velocity_ );
この例の中で、setTopic()はいかなるシグナルとも接続していません(これは直接呼び出されます)が、一部の他のユーザにとって有用となる場合に備えて、プライベート関数の代わりにパブリックなスロットとして定義するのは容易です。
void setTopic( const QString& topic );
ここでいくつかの内部スロットを宣言します。
protected Q_SLOTS:
sendvel()は現在の速度の値をROSのトピックに配信します。内部的には、それを1秒につき10回とこれを呼ぶタイマーに接続しています。
void sendVel();
updateTopic()はQLineEditからトピック名を読み、その結果でsetTopic()を呼び出します。
void updateTopic();
ここはprotectedなメンバー変数についての説明です。
protected:
制御エリアのウィジェットで、マウスイベントを速度司令に変えます。
DriveWidget* drive_widget_;
送出するROSのトピック名を入力するための1行のテキストエディタです。
QLineEdit* output_topic_editor_;
現在の送出トピックの名前です。
QString output_topic_;
速度司令のROSの配信者
ros::Publisher velocity_publisher_;
ROSノードハンドル
ros::NodeHandle nh_;
ドライブウィジェットからの最新の速度値
float linear_velocity_; float angular_velocity_;
teleop_panel.cpp
teleop_panel.cpp の全内容は: src/teleop_panel.cpp
ここはTeleopPanelクラスの実装です。TeleopPanelは以下の機能を満たします:
DriveWidget と QLineEditのGUI要素のコンテナとして振る舞う
- 速度司令をそれを1秒につき10回配信する(値が0であっても)
- ファイルから内部状態を保存し、復元する
コンストラクタの解説から始めます。オプションの親引数をスーパークラスのコンストラクタに渡す標準的なQtの手順を行い、を配信する速度に値0を設定をします。
TeleopPanel::TeleopPanel( QWidget* parent ) : rviz::Panel( parent ) , linear_velocity_( 0 ) , angular_velocity_( 0 ) {
次に、QHBoxLayoutの中でQLabel と QLineEditを使った、“output topic”テキストの入力領域をレイアウトします。
QHBoxLayout* topic_layout = new QHBoxLayout; topic_layout->addWidget( new QLabel( "Output Topic:" )); output_topic_editor_ = new QLineEdit; topic_layout->addWidget( output_topic_editor_ );
そして、コントロールウィジェットを生成します。
drive_widget_ = new DriveWidget;
コントロールウィジェット上にトピック領域をレイアウトします。
QVBoxLayout* layout = new QVBoxLayout; layout->addLayout( topic_layout ); layout->addWidget( drive_widget_ ); setLayout( layout );
出力を送るためにタイマーを生成します。モーターコントローラーはコントローラーが正しく機能しているかの確認を頻繁に行う必要があるので、値の変化が無くても速度値を再送し続けます。
ここで、QObjectのメモリ管理の振る舞いを利用します。“this”はその親である新しいQTimerに渡され、TeleopPanelのオブジェクトが破棄された時にQTimerはQObjectのデストラクタによって消去されます。よって、タイマーのポインタを保持している必要はないのです。
QTimer* output_timer = new QTimer( this );
次は、signal/slotの接続を作ります。
connect( drive_widget_, SIGNAL( outputVelocity( float, float )), this, SLOT( setVel( float, float ))); connect( output_topic_editor_, SIGNAL( editingFinished() ), this, SLOT( updateTopic() )); connect( output_timer, SIGNAL( timeout() ), this, SLOT( sendVel() ));
タイマーをスタートします。
output_timer->start( 100 );
コントロールウィジェットを使用不可で開始し、トピックを出力状態では開始しないようにします。
drive_widget_->setEnabled( false ); }
setVel()はDriveWidgetの出力に接続しており、マウスイベントによる変化のときに送信しています。ここは引数で与えられた値を記録しているにすぎません。次のコールバックタイマーが来るまで、データは実際には送られません。
void TeleopPanel::setVel( float lin, float ang ) { linear_velocity_ = lin; angular_velocity_ = ang; }
QLineEditからののトピック名を読み、output_topic_editor_のテキスト取得結果とともにsetTopic()を呼び出します。これはQLineEdit::editingFinished()に接続していて、ユーザがエンターかタブキーを押すか、フォーカスが他に移った時に送出します。
void TeleopPanel::updateTopic() { setTopic( output_topic_editor_->text() ); }
配信するトピック名をセットします。
void TeleopPanel::setTopic( const QString& new_topic ) {
トピック名が変化した時だけ実行されます。
if( new_topic != output_topic_ ) { output_topic_ = new_topic;
もしトピックに空の文字列が入ってきたら、何も配信しません。
if( output_topic_ == "" ) { velocity_publisher_.shutdown(); } else {
右辺の代入値で、古いvelocity_publisher_を破棄することで、古いトピック配信は終了します。nh_advertise()の呼び出しは新しいトピック名の配信データを返します。
velocity_publisher_ = nh_.advertise<geometry_msgs::Twist>( output_topic_.toStdString(), 1 ); }
rviz::PanelがconfigChanged()のシグナルを定義しています。このシグナルの放出は、このパネルの中の何か変化して保存されたconfigファイルに影響を及ぼすことを、RVizに通知します。最終的に、このシグナルはトップレベルのrviz::VisualizationFrame上でQWidget::setWindowModified(true)の呼び出しを起こして、変更が保存されていないことを示す小さなアスタリスク(“*”)がウインドウのタイトルバーに現れます。
Q_EMIT configChanged(); }
出力トピックが空の時、コントロールウィジェットをグレー表示にします。
drive_widget_->setEnabled( output_topic_ != "" ); }
もしROSが落ちておらず、配信者のvelocity_publisher_に有効なトピック名があるとき、制御速度値を配信します。
void TeleopPanel::sendVel() { if( ros::ok() && velocity_publisher_ ) { geometry_msgs::Twist msg; msg.linear.x = linear_velocity_; msg.linear.y = 0; msg.linear.z = 0; msg.angular.x = 0; msg.angular.y = 0; msg.angular.z = angular_velocity_; velocity_publisher_.publish( msg ); } }
このパネルから、引数で与えられたConfigオブジェクトへ、全てのconfigurationデータを保存します。save()を親クラス上で呼び出して、クラスidとパネル名を保存することが、ここでは重要です。
void TeleopPanel::save( rviz::Config config ) const { rviz::Panel::save( config ); config.mapSetValue( "Topic", output_topic_ ); }
引数で与えられたConfigオブジェクトから、全てのconfigurationデータをこのパネルにロードする
void TeleopPanel::load( const rviz::Config& config ) { rviz::Panel::load( config ); QString topic; if( config.mapGetString( "Topic", &topic )) { output_topic_editor_->setText( topic ); updateTopic(); } }
} // end namespace rviz_plugin_tutorials }}}
このクラスについてのpluginlibの宣言。どんな名前空間範囲の外ででも、pluginlib::ClassLoaderでロード可能でなければならない全てのクラスは、それぞれの.cppファイルの中でこの2行を記述しておかなければなりません。
#include <pluginlib/class_list_macros.h> PLUGINLIB_EXPORT_CLASS(rviz_plugin_tutorials::TeleopPanel,rviz::Panel )
drive_widget.h
drive_widget.hの全内容は:src/drive_widget.h
DriveWidgetはマウスのY値を直線速度に、X値を角速度に変換する制御を実装しています。
最大限の再利用性のために、このクラスはユーザインタラクションとこのウィジェット内部の表示のみの機能を有しています。いかなるROSをやRVizの呼び出しもしません。Qtのシグナルを介してのみ、データを外に伝えます。
class DriveWidget: public QWidget { Q_OBJECT public:
このクラスはpluginlib::ClassLoaderによってインスタンスを生成しないので、コンストラクタには制限がありません。
DriveWidget( QWidget* parent = 0 );
独自のペインティングのために、QWidget::paintEvent()をオーバライドしています。
virtual void paintEvent( QPaintEvent* event );
マウスの状態を追跡しつづけるために、マウスイベントとleaveEvent()をオーバライドしています。
virtual void mouseMoveEvent( QMouseEvent* event ); virtual void mousePressEvent( QMouseEvent* event ); virtual void mouseReleaseEvent( QMouseEvent* event ); virtual void leaveEvent( QEvent* event );
良い表示サイズについての若干のアイデアをレイアウト・マネージャに与えるために、sizeHint()をオーバライドしています。
virtual QSize sizeHint() const { return QSize( 150, 150 ); }
速度が変化したらいつでもoutputVelocity()を発行します。
Q_SIGNALS: void outputVelocity( float linear, float angular );
mouseMoveEvent()とmousePressEvent()は速度を算出するための同種の数式が必要なので、ここに追加しています。
protected: void sendVelocitiesFromMouse( int x, int y, int width, int height );
速度0を発行する関数
void stop();
最後に、メンバ変数です。
float linear_velocity_; // In m/s float angular_velocity_; // In radians/s float linear_scale_; // In m/s float angular_scale_; // In radians/s };
drive_widget.cpp
drive_widget.cppの全内容は:src/drive_widget.cpp
DriveWidgetのコンストラクタは、親ウィジェットをスーパークラスのコンストラクタに渡す通常のQtの処理を行い、メンバ変数を初期化します。
DriveWidget::DriveWidget( QWidget* parent ) : QWidget( parent ) , linear_velocity_( 0 ) , angular_velocity_( 0 ) , linear_scale_( 10 ) , angular_scale_( 2 ) { }
このpaintEvent()は車輪の動きを表現する2つの円弧状の矢を描画するために複雑になっています。ここはRVizのプラグインの作り方を学ぶことには特に関係していないので、部分的に解説します。
void DriveWidget::paintEvent( QPaintEvent* event ) {
背景色とクロスヘア線の色はウィジェットが使用可か不可によって違う色で描画されます。これは制御が有効かどうかの、良い視覚的な指示になります。
QColor background; QColor crosshair; if( isEnabled() ) { background = Qt::white; crosshair = Qt::black; } else { background = Qt::lightGray; crosshair = Qt::darkGray; }
メインのビジュアルは、正方形で、ウィジェットの領域の中心に配置されています。ここは正方形のサイズと、メインビジュアルの水平と垂直のオフセットを計算しています。
int w = width(); int h = height(); int size = (( w > h ) ? h : w) - 1; int hpad = ( w - size ) / 2; int vpad = ( h - size ) / 2; QPainter painter( this ); painter.setBrush( background ); painter.setPen( crosshair );
バックグラウンドの四角を描画する
painter.drawRect( QRect( hpad, vpad, size, size ));
四角の中のクロスヘア線を描画する
painter.drawLine( hpad, height() / 2, hpad + size, height() / 2 ); painter.drawLine( width() / 2, vpad, width() / 2, vpad + size );
もしウィジェットが使用可で速度がゼロでない場合は、ディフドライブロボットがその速度を維持した場合の、ロボットの車輪が追従可能なパスを示すいくつかの明るい緑色の矢を描きます。
if( isEnabled() && (angular_velocity_ != 0 || linear_velocity_ != 0 )) { QPen arrow; arrow.setWidth( size/20 ); arrow.setColor( Qt::green ); arrow.setCapStyle( Qt::RoundCap ); arrow.setJoinStyle( Qt::RoundJoin ); painter.setPen( arrow );
このコードは直線速度と角速度で定義された中心弧にそって進みます。各ステップで、左右の車輪のある場所を計算し、left_track と right_trackの配列に計算結果の点を集めます。
const int step_count = 100; QPointF left_track[ step_count ]; QPointF right_track[ step_count ]; float half_track_width = size/4.0; float cx = w/2; float cy = h/2; left_track[ 0 ].setX( cx - half_track_width ); left_track[ 0 ].setY( cy ); right_track[ 0 ].setX( cx + half_track_width ); right_track[ 0 ].setY( cy ); float angle = M_PI/2; float delta_angle = angular_velocity_ / step_count; float step_dist = linear_velocity_ * size/2 / linear_scale_ / step_count; for( int step = 1; step < step_count; step++ ) { angle += delta_angle / 2; float next_cx = cx + step_dist * cosf( angle ); float next_cy = cy - step_dist * sinf( angle ); angle += delta_angle / 2; left_track[ step ].setX( next_cx + half_track_width * cosf( angle + M_PI/2 )); left_track[ step ].setY( next_cy - half_track_width * sinf( angle + M_PI/2 )); right_track[ step ].setX( next_cx + half_track_width * cosf( angle - M_PI/2 )); right_track[ step ].setY( next_cy - half_track_width * sinf( angle - M_PI/2 )); cx = next_cx; cy = next_cy; }
そして、軌道の配列が満たされると、太い緑の線で左右それぞれをひと描きします。
painter.drawPolyline( left_track, step_count ); painter.drawPolyline( right_track, step_count );
ここはそれぞれの矢の先がどの方向を指すか(前方が後方か)を決定します。これは1ステップ(step_dist) で中心が進んできた弧の長さと、車輪が進んできた弧の長さ(half_track_width * delta_angle)の比較で実現します。
int left_arrow_dir = (-step_dist + half_track_width * delta_angle > 0); int right_arrow_dir = (-step_dist - half_track_width * delta_angle > 0);
矢の先の形状を作るためにMiterJoinを使う。これで尖った先ができます。
arrow.setJoinStyle( Qt::MiterJoin ); painter.setPen( arrow );
それぞれの矢の先のためのポリラインを計算し描画する。このコードはもっと洗練できるはずです。
float head_len = size / 8.0; QPointF arrow_head[ 3 ]; float x, y; if( fabsf( -step_dist + half_track_width * delta_angle ) > .01 ) { x = left_track[ step_count - 1 ].x(); y = left_track[ step_count - 1 ].y(); arrow_head[ 0 ].setX( x + head_len * cosf( angle + 3*M_PI/4 + left_arrow_dir * M_PI )); arrow_head[ 0 ].setY( y - head_len * sinf( angle + 3*M_PI/4 + left_arrow_dir * M_PI )); arrow_head[ 1 ].setX( x ); arrow_head[ 1 ].setY( y ); arrow_head[ 2 ].setX( x + head_len * cosf( angle - 3*M_PI/4 + left_arrow_dir * M_PI )); arrow_head[ 2 ].setY( y - head_len * sinf( angle - 3*M_PI/4 + left_arrow_dir * M_PI )); painter.drawPolyline( arrow_head, 3 ); } if( fabsf( -step_dist - half_track_width * delta_angle ) > .01 ) { x = right_track[ step_count - 1 ].x(); y = right_track[ step_count - 1 ].y(); arrow_head[ 0 ].setX( x + head_len * cosf( angle + 3*M_PI/4 + right_arrow_dir * M_PI )); arrow_head[ 0 ].setY( y - head_len * sinf( angle + 3*M_PI/4 + right_arrow_dir * M_PI )); arrow_head[ 1 ].setX( x ); arrow_head[ 1 ].setY( y ); arrow_head[ 2 ].setX( x + head_len * cosf( angle - 3*M_PI/4 + right_arrow_dir * M_PI )); arrow_head[ 2 ].setY( y - head_len * sinf( angle - 3*M_PI/4 + right_arrow_dir * M_PI )); painter.drawPolyline( arrow_head, 3 ); } } }
ここで受け取った全てのマウス動作イベントは速度を送信します。事前にマウス押下イベントがあれば、ウィジェットの中では、Qtはマウス動作イベントを送るだけだからです。
void DriveWidget::mouseMoveEvent( QMouseEvent* event ) { sendVelocitiesFromMouse( event->x(), event->y(), width(), height() ); }
もちろん、マウス押下イベントは速度値も送信すべきです。
void DriveWidget::mousePressEvent( QMouseEvent* event ) { sendVelocitiesFromMouse( event->x(), event->y(), width(), height() ); }
マウスがウィジェットから離れていて、ボタンは押下されたままの時、leaveEvent()は起きません。(Qtからのデフォルト状態によって)マウスは"握られた状態"だからです。しかしながら、マウスがウィジェットの外にドラッグされて他のボタンが押された時(または他のウインドウマネージャの何かが起きるといった場合)、leaveEvent()は起きますが、mouseReleaseEvent()は起きません。このイベントを捕捉すること無ければ、ユーザ制御無しでロボットを動かさないまましておけます。
void DriveWidget::leaveEvent( QEvent* event ) { stop(); }
停止の通常の方法:マウスボタンを放す。
void DriveWidget::mouseReleaseEvent( QMouseEvent* event ) { stop(); }
四角の中心部に相対したXとYのマウス位置を元にした、直線速度と角速度を計算し発行します。
void DriveWidget::sendVelocitiesFromMouse( int x, int y, int width, int height ) { int size = (( width > height ) ? height : width ); int hpad = ( width - size ) / 2; int vpad = ( height - size ) / 2; linear_velocity_ = (1.0 - float( y - vpad ) / float( size / 2 )) * linear_scale_; angular_velocity_ = (1.0 - float( x - hpad ) / float( size / 2 )) * angular_scale_; Q_EMIT outputVelocity( linear_velocity_, angular_velocity_ );
メインイベントのループの次のタイミングでこのウィジェットを再描画するよう、update()はQWidget関数でスケジューリングします。速度値は変化していて、矢はその変化に合うように書き直す必要があるので、この処理が必要です。
update(); }
止め方:0の速度値を発行する!
void DriveWidget::stop() { linear_velocity_ = 0; angular_velocity_ = 0; Q_EMIT outputVelocity( linear_velocity_, angular_velocity_ ); update(); }
プラグインをビルドする
プラグインをビルドするには、通常の“rosmake”を実行します。
rosmake rviz_plugin_tutorials
プラグインをエクスポートする
プラグインを他のROSパッケージから使えるようにする(今回の場合はRVizから使えるようにする)には、“plugin_description.xml”ファイルが必要です。このファイルは実際はどんな名前でもいいのですが、同じ名前で特定できるようにプラグインのパッケージの“package.xml”ファイルの中で以下のように設定します:
<export> <rviz plugin="${prefix}/plugin_description.xml"/> </export>
plugin_description.xmlの中身は以下のようになります:
<library path="lib/librviz_plugin_tutorials"> <class name="rviz_plugin_tutorials/Teleop" type="rviz_plugin_tutorials::TeleopPanel" base_class_type="rviz::Panel"> <description> A panel widget allowing simple diff-drive style robot base control. </description> </class> <class name="rviz_plugin_tutorials/Imu" type="rviz_plugin_tutorials::ImuDisplay" base_class_type="rviz::Display"> <description> Displays direction and scale of accelerations from sensor_msgs/Imu messages. </description> <message_type>sensor_msgs/Imu</message_type> </class> <class name="rviz_plugin_tutorials/PlantFlag" type="rviz_plugin_tutorials::PlantFlagTool" base_class_type="rviz::Tool"> <description> Tool for planting flags on the ground plane in rviz. </description> </class> </library>
最初の行は、コンパイル済みのライブラリがlib/librviz_plugin_tutorialsにあるという意味です。(末端の”.so”は、OSごとにpluginlibによって付加されている)このパスはパッケージのトップディレクトリに関連しています。
<library path="lib/librviz_plugin_tutorials">
次のセクションはTeleopPanelについて記述しているクラスのエントリです。
<class name="rviz_plugin_tutorials/Teleop" type="rviz_plugin_tutorials::TeleopPanel" base_class_type="rviz::Panel"> <description> A panel widget allowing simple diff-drive style robot base control. </description> </class>
ここには名前、型、基底クラス、そしてクラスの説明を明記します。ネームフィールドは最初の2つの文字列の組み合わせを、ソースファイルのPLUGINLIB_DECLARE_CLASS()マクロに与えたものでなければなりません。“package”名、“/”(スラッシュ)、そしてクラスの“display name”になるでしょう。“display name”はユーザインタフェースでクラスとして使われる名前です。
型のエントリは完全修飾のクラス名で、どんな名前空間もこの中に含まれていなければなりません。
base_class_typeは通常、rviz::Panel、rviz::Display、rviz::Tool、rviz::ViewControllerの一つです。
このサブセクションの説明はクラスの単純なテキスト説明で、クラス選択ダイアログとDisplaysパネルのヘルプエリアに表示されています。このセクションはハイパーリンクを含むHTMLを保持することができますが、マークアップは、XMLマークアップと解釈されることを避けるために使用をさけなければなりません。例えば、リンクタグはこのようになるでしょう:<a href="my-web-page.html">
Diplayプラグインは複数のmessage_typeタグを持つことができ、その配信をまず選択しているDisplayを追加した時のRVizで使われます。
Pluginを試してみる
RVizのプラグインをコンパイルしエクスポートしたら、いつも通りrvizを走らせるだけです:
rosrun rviz rviz
そして、rvizはpluginlibを使って、rvizにエクスポートされた全てのプラグインを見つけます。
“Panels”メニューを開いて、その中にある“Add New Panel”ボタンをクリックすることで、TeleopPanelを追加します。これはこの中にある“Teleop”でパネルクラス選択ダイアログを起動せねばなりません(ここでは“rviz_plugin_tutorials”)。
もし“Teleop”がPanel Typesのリストに無かったら、RVizのコンソールの出力からプラグインのロードに関するエラーメッセージを確認します。よくある問題として:
plugin_description.xmlファイルが無い
package.xmlファイルの中にプラグインのエクスポートする記述がない
plugin_description.xmlからの、ライブラリファイル(librviz_plugin_tutorials.soのような)の参照が正しくない
一度TeleopパネルをRVizに追加したら、geometry_msgs/Twistの速度司令を配信するトピック名を入力するだけです。一度、“Output Topic”領域に空でない文字列が入ると、制御の正方領域は明るくなり、マウスイベントを受けつけるでしょう。制御エリアの中でマウスボタンを押下したままにすると、中心からのマウス位置に相対したY位置を元にした直線速度と、中心からのマウス位置に相対したX位置を元にした角速度を送信します。
次のステップ
ディフドライブ・ロボットに適切な命令速度を送出するので、このTeleopパネルはそのままで役に立つかもしれません。しかしながら、以下の作業でより有用なTeleopパネルになるでしょう:
- 直線速度と角速度のスケールを調整可能にする
- 速度値の強制的な最大値設定
- ロボット幅パラメータを調整可能にして、カーブした正確な矢でロボットが通過する弧表示する
- ホロノミックドライブが可能なPR2のようなロボットのための“strafe” モード (たぶんシフトキーを押しながら実行する)