seed-solutions / aero-ros-pkg Goto Github PK
View Code? Open in Web Editor NEWAERO (SEEDNOID) ROS Package
AERO (SEEDNOID) ROS Package
:move-waist
の最短時間が 5.0 秒になるようにしました.
実装的には,
aero_description/aero_wheels_typeC/controllers/AeroTorsoController.cc
のTorsoKinematics()
の中で,
float time_from_start = std::max(1.0 * time_scale, 5.0);
としているだけです.
実機で正しい挙動であることを確認済です.
garlic のaero_description/add-minimum-value-for-time-from-start-in-move-waist
ブランチで
改良されていて,しかし例によって PR は出せていない状態なので,PR を出してマージされてから Close します.
今後コマンドが増えたときにコントローラの大幅な変更を避けるため、何かしらのAPIがあるといいかもしれません。
機能にもよりますが、ROSのサービス経由で例えば
次の指令ではこのジョイントだけ動かす、というリクエストを送ると、現在使っているコントローラからどんな値が送られても、該当しないジョイントの値は無視される。
となっていると、コントローラ側を変えずに機能の追加ができそうですね。
コントローラの仕様は固定して、リクエストを送ると必要に応じてコントローラの振る舞いが変わるとなっていれば互換性が取りやすいかもしれません。
いずれにしても現在存在する機能を一度リストアップして、サービスに落とし込めそうかというところからですね。
(send *ri* :base-coords)
とすると,
(send *ri* :go-pos)
の積算値を返すようにしました.
積算値は cascaded-coords で,角度も入れてあります.
実装的には,単に:go-pos
で送られた値を積算していって,
aero-upper-interface
のスロット変数base-coords
で持っているだけとなります.
現在,garlic のaeroeus/add-base-coords
ブランチで対応済ですが,
PR を出せていないので,PR を出してマージされ次第,Close したいと思います.
typeFのAeroTorsoControllerを見てて気になったのですが
LegTable
という関数がswitch文で90個くらい分岐していて,
switch文は要するに最悪時if文がcaseの数だけ実行されているので
場合によってとんでもないオーバーヘッドになってるのではないかという気がしています.
実際逆アセンブルしてみると,
leus@scorzonera:~/ros/indigo/devel/lib/aero_startup$ objdump -d aero_torso_controller_node | grep jmpq
~~~略~~~
4269fc: e9 0c 08 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426a13: e9 f5 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426a2a: e9 de 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426a41: e9 c7 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426a58: e9 b0 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426a6f: e9 99 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426a86: e9 82 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426a9d: e9 6b 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426ab4: e9 54 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
426acb: e9 3d 07 00 00 jmpq 42720d <_Z8LegTablef+0x872>
~~~これが90行くらい続く~~~
で,多分switchでなくて配列アクセスにすれば単純なメモリアドレス指定になってスッキリし,
定数時間で終了する関数になるはずです.
現状のeusがあんまりにもあんまりなので,なんとかできないかな.
まずurdfからeusに直接持ってくるのは,
ヒューマノイドでないためにむずかしそう.
そもそも上下で二台の別のロボットを連結して使っているという四脚時代の名残があり,
それはできればまた四脚に戻したいなど起こった時に拡張性として残したい.
eusモデルだけなら,
単純に下半身だけモデルを作って上半身をassocしてしまえばいい.
ただしurdfが変わった時に手動でやりましょう,というのは嫌.
そもそも #115 が未解決.
#115 にも関連しますが,
最低限gazeboでモデルが表示できるところまで行って公開しましょう.
for example:
meta = scale * rad2Deg * r_wrist_p_joint; //4
meta = scale * rad2Deg * r_dgripper_joint; //5
// meta = scale * rad2Deg *r_hand //5
meta = scale * LegTable(rad2Deg * (knee_joint - hip_joint)); //0
meta = scale * LegTable(rad2Deg * hip_joint); //1
in the headers/Angle2Stroke.hh
would generate
_strokes[4] = scale * rad2Deg * _angles[4]; //4
_strokes[5] = scale * rad2Deg * _angles[5]; //5
// _strokes[6] = scale * rad2Deg *r_hand //5
_strokes[7] = scale * LegTable(rad2Deg * (_angles[8] - _angles[7])); //0
_strokes[8] = scale * LegTable(rad2Deg * _angles[7]); //1
in the aero_startup/aero_hardware_interface/Angle2Stroke.cc
This seems to happen for commented lines in the Constants.hh file too.
:move-waist すると,その中で wait-interpolation してくれるようにしました.
実装的には,
aero_description/aero_wheels_typeC/controllers/AeroTorsoController.cc
のTorsoKinematics()
の中で,sleepするようにしただけです.
実機で正しい挙動であることを確認しました.
現在,garlic のaero_description/sleep-in-move-waist
ブランチで改良されていて,
しかし例によって PR は出せていない状態なので,PR を出してマージされてから Issue を Close します.
なかった and ないと一番困るところなので,書き始めています.
SRT2016で使用するシングルアームのモデル関連ファイルをaero-ros-pkg-prereleaseへいれる流れですが、
1、aero-ros-pkg-prereleaseをfork
2、forkで複製したリポジトリにモデルファイルをcommit
3、pull request
といった流れであっていますでしょうか。
ぱっとみでキャスト関連のwarningが出てます.対処しましょう.
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc: In member function ‘aero::navigation::pose aero::navigation::AeroMoveBase::dX(std::vector<double>, float)’:
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘- _vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator<double> >(0ul)’ from ‘__gnu_cxx::__alloc_traits<std::allocator<double> >::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
{-_vels[0], _vels[1], -_vels[2], _vels[3]};
^
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘- _vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator<double> >(0ul)’ from ‘__gnu_cxx::__alloc_traits<std::allocator<double> >::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘_vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator<double> >(1ul)’ from ‘__gnu_cxx::__alloc_traits<std::allocator<double> >::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘_vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator<double> >(1ul)’ from ‘__gnu_cxx::__alloc_traits<std::allocator<double> >::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘- _vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator<double> >(2ul)’ from ‘__gnu_cxx::__alloc_traits<std::allocator<double> >::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘- _vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator<double> >(2ul)’ from ‘__gnu_cxx::__alloc_traits<std::allocator<double> >::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘_vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator<double> >(3ul)’ from ‘__gnu_cxx::__alloc_traits<std::allocator<double> >::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘_vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator<double> >(3ul)’ from ‘__gnu_cxx::__alloc_traits<std::allocator<double> >::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:76:32: warning: narrowing conversion of ‘(((((double)(Vx * 2.0e+0f)) * 3.1415926535897931e+0) * 7.5999997556209564e-2) * ((double)_dt))’ from ‘double’ to ‘float’ inside { } [-Wnarrowing]
return {Vx * 2*M_PI * radius * _dt,
^
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:77:30: warning: narrowing conversion of ‘(((((double)(Vy * 2.0e+0f)) * 3.1415926535897931e+0) * 7.5999997556209564e-2) * ((double)_dt))’ from ‘double’ to ‘float’ inside { } [-Wnarrowing]
Vy * 2*M_PI * radius * _dt,
^
/home/travis/catkin_ws/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:78:44: warning: narrowing conversion of ‘((((double)_dt) * 3.5814155801515208e+0) / 1.2619882914178727e+2)’ from ‘double’ to ‘float’ inside { } [-Wnarrowing]
max_velocity * radius * M_PI * _dt / (sqrt(2) * Radius * 300)};
^
wheelsとtypeCのモデルを切り替えると解けなくなるikがありました.
どちらのモデルが正しいのでしょうか.
いつもお世話になっております。THKの近藤と申します。
現在single-arm用のmoveitによるモデルの作成を行っていますが、moveit setup assistantにおいてsrdfモデルを生成する際、ik用に作成するリンクのtip_link.eef_linkをどの位置に指定しているか教えて頂きたいです。よろしくお願い致します。
もともと確率的に起きていたことが,最近ほぼ確実に起きるようになり,
まともにaeroを動かせなくなりました.
[ WARN] [1466063659.709798767]: [/larm_controller/follow_joint_trajectory_actio\
n] action server is not found
[ WARN] [1466063659.709903718]: goal=0, cancel=0, feedback=0, result=0
[ WARN] [1466063659.709945861]: #<controller-action-client #X83485b0 /larm_cont\
roller/follow_joint_trajectory_action> is not respond, AeroUpperRobot-interface\
is disabled
((lambda nil (send #<aero-upper-interface #X8ff9d98> :robot-interface-simulatio\
n-callback)) lisp::count-up-timer)
[ WARN] [1466063659.879116758]: ROSEUS is already installed as /default_robot_i\
nterface_1466063656467712448
/opt/ros/indigo/share/euslisp/jskeus/eus/Linux64/bin/irteusgl: ERROR th=0 numbe\
r expected *** buffer overflow detected ***: /opt/ros/indigo/share/euslisp/jske\
us/eus/Linux64/bin/irteusgl terminated
======= Backtrace: =========
でコアダンプして落ちます.
そもそもこの情報だけでは何を疑っていいのかもわかりません.
またなぜ直近で頻度が上がったのかも理解できません.
作業記録等々です.
ロボットの種類が増えてきたのでmodelsディレクトリ以下を整理したいと思います.
manual
.wrl > model mesh data
.csv > angle-stroke conversion data
.yaml > for eus
generated
meshes directory
*.conf
*controller_config.yaml
*_nosim.*
*.l
*.urdf ?
csv変換とurdf生成まわりへの影響.
grep results:
./make_stroke_to_angle_header.sh: file="$(rospack find aero_description)/models/${joint_name}.csv"
./make_angle_to_stroke_header.sh: file="$(rospack find aero_description)/models/${joint_name}.csv"
./make_angle_to_stroke_header.sh: file="$(rospack find aero_description)/models/${joint_name_a}.csv"
./make_angle_to_stroke_header.sh: file="$(rospack find aero_description)/models/${joint_name_b}.csv"
./create_urdf.sh:# generates : aero_description/models/aero.urdf
./create_urdf.sh: urdf="$(rospack find aero_description)/models/${urdf_name}.urdf"
./create_urdf.sh: output_file="$(rospack find aero_description)/models/${3}.urdf"
提案構成:
aero_description/{robot}/models
|
-- /wrl (.wrl + .yaml, complete)
-- /csv (.csv, reference allowed)
-- /gen (all generated files)
aero_description/models
|
-- {upper}.l
-- {lower}.l
-- aero.urdf
wrlはまるごとディレクトリに置く(他のロボットと同じモデルを使う場合でも).
これは万一openhrpを走らせるときに破綻しないようにするためです.
一方csvは原則として重複は置かないことにします.
otherwise 重複部位を修正したときに、全ロボットの該当ファイルを修正することになり、煩雑です.
modification:
in headers/*.hh
@define ShoulderPitchInvTable from shoulder-p offset 0
> @define ShoulderPitchInvTable from {robot}/shoulder-p offset 0
for the urdf generation, change search path in create_urdf.sh
models directory will be setup when running setup.sh (i.e. inside models directory will be cleaned before urdf creation, .l will be copied from /gen)
これに加えてopenhrpの生成スクリプトがあるといいかもしれません.
(cp -r {robot}/models/wrl /models, modify CMakeLists, cp -r /models {robot}/models/gen, build)
もとのissueが長すぎて移設が難しかったので新規issueにします.
台車制御はtwist経由でジョイスティックから行いたい.
from @nagahama-jsk
@hyaguchijsk 先生,
柔らかくて薄いもの(例:紙)を,パワーグラスプせずに握りたいという要望が出ています.
現状では,おそらく:graspや:ungraspだけでグリッパを操作するようにして,
:angle-vectorの中ではrarm_thumb_pなどがコメントアウトされている,という状況かと思いますが,
要望に応えるためには,グリッパにも関節角度指令を送れる必要があると思います.
グリッパの今後の方針としては,どのような感じでしょうか?
さっと確認しましたが,
grasp,ungraspは
aero_description/aero_four_legs/controllers/AeroHandController.ccが中身で,
ここを少し書き換えて直接ストロークを送れるようにすれば良いかと思いますが,
ちなみにeus側の指令がコメントアウトされているのは、:graspしたときに自動で調整した把持指令がeusモデルに反映されなくて、次にeusから全身指令を送ったときに把持指令が変わってしまう(把持が解除されてしまう)といった経緯からです。
なので、すべてコントローラ側で把持指令を管理するのに賛成です。指令値把持できる関数を追加すると良いと思います。
以下の未コミットはmasterにpushするのが正解な気がしますが。pushして大丈夫ですか。
aero_description/aero_wheels/headers/Angle2Stroke.hh
meta = -scale * rad2Deg * r_wrist_y_joint;
meta = scale * right_wrist.one;
meta = scale * right_wrist.two;
- meta = -scale * (rad2Deg * r_thumb_joint + 50.0) * 0.18 * 2.0;//2.0;//1.2
+ meta = -scale * (rad2Deg * r_thumb_joint + 50.0) * 0.18;//2.0;//1.275;
meta =
scale * ShoulderPitchTable(-rad2Deg * l_shoulder_p_joint);
aero_description/aero_wheels/headers/Stroke2Angle.hh
deg2Rad * WristRollInvTable(-fabs(right_wrist_roll_stroke))
* (right_wrist_roll_stroke >= 0 ? 1 : -1);
meta =
- deg2Rad * (scale * can_r_hand * 5.556 * 0.5 + 50.0); // center
+ deg2Rad * (scale * can_r_hand * 5.556 + 50.0); // center
meta = 0;
meta = 0;
meta =
- -deg2Rad * (scale * can_r_hand * 5.556 * 0.5 + 50.0); // center
+ -deg2Rad * (scale * can_r_hand * 5.556 + 50.0); // center
meta = 0;
meta = crotch_angle;
aero_startup/aero_move_base/AeroMoveBase.txt
- 1.0,1.0,1.278
+ 0.917,1.0,1.311
というのと、体内で動作確認が済んでPRがマージされたのを確認したらブランチはテストブランチのままにせず、masterに切り替えるようお願いします。
あと、ハンドの倍率については外部スクリプトでファームウェアをその都度、直接書き換えたりできないんだろうか。。。
コントローラ生成ファイルの倍率を修正すると変なコミットが残ってよくわからなくなるので、例えばAPCHand.py、TomatoHand.py、DefaultHand.pyとかをあらかじめ用意しておいて、これを実行するとコントローラはそのままでハンドの部分だけ倍率修正できるとうれしい。
(正直なところ、そもそもハンドは改造しないで欲しいというのが個人的に思うところではありますが。。。改造するくらいならAPCのときのバキュームみたいに掴むアタッチメント+専用コマンドにしません?)
昇降と台車制御がうまいことバッティングすると昇降軸のサーボが切れることがあるようです.
今後公開されることを踏まえると,
不特定多数からのPReqが届き,それらの合否判定をするためにはテストが必須です.
travisを使うと,
PReqが届いた時点で自動的にテストを行い,判定を行うことができるようになります.
travisのテストが通らなければそのPReqを保留して修正してもらうようにすれば良いです.
テストの粒度として,
まずはコントローラ周り単独でROSを用いないテストを組み,
その後必要となればROS周りも入れていく,というのがいいのかな,と思っています.
#74 で発覚しましたが,別の問題も含むのでこちらで議論しましょう.
右肩のピッチ角(r_shoulder_p)が急に動く現象が起こりました。
まだ特定のeusプログラム内でしか確認されていません。
状況としては、
1,手を胸の前に置く
2,肘を上げたポーズを取る
3,send ri :ungrasp :larmする
するとr_shoulder_pが3のタイミングで急に動き始めました。
他の角度には3の前後で影響は見当たりませんでした。
3はsend ri :ungrasp :rarmなどでも確認されています。
r_shoulder_pに関する値の推移としては
1時点
desired 0.0
actual 0.0
2時点
command -1.5586602672022858
desired 0.0
actual -1.5452097654342651
3時点
desired -0.0
actual -0.619846761226654 (ここから腕が干渉して動けない)
2時点でdesiredとactualが違うのは不自然なのでコントローラ側で何か起こっているような気がします。
(send *ri* :angle-vector (send *aero* :angle-vector) time)
のtimeを送らない方法を考えたいです.
というのは,どのような姿勢を今とっているかを考えず大体定数で入れていますが,
それだと目標から遠い時は早すぎ,近い時は無駄に遅いです.
configuration space内での距離とアクチュエータの最高速度から最短時間が計算できるはずです.
ただし,ここでいうconfiguration空間はstroke空間が好ましいため,
aeroeusはおろかrosまで降りてきてしまうと計算するすべがなく,
コントローラで返すのがよい,となるのではないでしょういか.
従来のAeroBaseControllerにて(send *ri* :go-pos 1 0 0)
と(send *ri* :go-pos 10 0 0)
とで移動量が変わらず、Xの値に24,48,72と24の倍数を入力すると段階的に移動量が増えていきます。y方向の移動についても同様です。
新台車のコントローラ作成に際してAeroBaseController.ccの車輪径”radius"を50から76に変更すると、36の倍数ごとに移動量が増加するようになりました。
AeroControllerNodeかUnusedAngle2Strokeのバグのようです。
現在、関節値と同時にセンサ値を受けとるようにしています。(Horisu/wrist_sensor_testブランチ)
まだ整理しきれていませんがloadPoseAero reset-poseやハンドコントローラの指令は受け取れますが、
以下のような指令を送ると
rostopic pub --once /aero_controller/command trajectory_msgs/JointTrajectory "header:
seq: 0
stamp:
secs: 5
nsecs: 0
frame_id: ''
joint_names:
- 'r_wrist_y_joint'
points:
- positions: [0]
velocities: [0]
accelerations: [0]
effort: [0]
time_from_start: {secs: 5, nsecs: 0}"
publishing and latching message for 3.0 seconds
*** Error in `/home/grxuser/ros/indigo/devel/lib/aero_startup/aero_controller_node': free(): invalid next size (fast): 0x00007f3b0c000f00 ***
エラーが出て止まります。
AeroControllerNode.cc内のupper用のref_strokesがfree出来ないようだとまではわかったのですが、この先がわかりかねます。
先週聞き取った内容ですが,以下のとおりでしょうか?
間違っていたら訂正をお願いします.
このままだと公開できるクォリティにないです.
AeroHandControllerのgraspで、一度握った後実際の角度に合わせて握る角度を調節する時、手が一度開いてから調節した角度に戻ります。
/aero_controller/statusのdesireや/aero_controller/commandは期待通りの値が出ていて、間に手が開く値は確認されていません。
larm,rarmの両方で同じ現象が確認されています。
一度手が開いてはしまいますが、握り直した後の握る力は良好です。
When a service definition is changed in AeroTorsoController.cc, running setup.sh does not result in the new edited service being generated.
Executing
$ cd aero_startup
$ catkin bt
is required to get the new service generated.
最初電源入れたときのポーズをreset-manip-poseにしたい。というのも、現在のreset-manip-poseがマニピュレーションに全く最適じゃない(ポーズが机などに干渉する恐れがある、IKが解きやすくなっているとも思えない、ビジョン的にオクルージョンを起こす)
一番簡単な方法はaero-interface.lで:reset-manip-poseというメソッドを作って上書くことだろうか。
と、さっとPRを見た感じだとaero-interface.l まわりで既に2つ出ているね。
#45 でポーズまわりをいじっているっぽいので、ついでにここで初期姿勢の角度をまるごと変えるといいかも。
また、 #32 でmin,maxを変えているっぽいので、腰のピッチリミットを40から30に修正すると良いですね。
@Horisu 修正頼めるかな?
これらの変更を加えたら、これらのPRをマージしたいと思います。
2つ同じファイルを編集したPRがあるので、片方をマージしてから、もう片方のPRでPullして、という作業が必要な気がする。
現状のmodels以下をコミットしてしまっても問題ないでしょうか?
Not high priority, however, below is something we might have to consider.
Also, for compatibility with the single arm robot, ./setup.sh
has to be fixed in the near future.
Currently, it seems the setup is done using ./setup.sh
.
However, compiling the controllers on a local computer should be unnecessary.
Before (meaning end of last year), the setup process for the local computer was:
catkin build aero_description
.roscd aero_description/scripts; ./install_srv.sh
and then, catkin b aero_startup
.roscd aero_description/scripts; ./create_urdf.sh aero_wheels aero_upper aero-wheels
.catkin b aeroeus
However, some of the scripts seem to have phased out.
Now, the question is should we create a ./local_setup.sh
to get things back?
I find some advantages in doing this
./setup.sh
is slow. The script creating the stroke-angle conversion table is not efficient.あとでもっとちゃんとしたドキュメントを作りますが、Kinectセンサから点群を取ってきたり画像を取ってきたりする方法を紹介しておきます。
ただし、画像と点群、同時にストリーミングすることは想定されていないのと、1秒より早い周期でストリームを受け取ることは想定されていない(1秒より早く設定することはできますが、ちゃんと返ってくるかは不明)ので、
は違う方法を模索した方がいいかもしれません。
あと最近Xtion環境ができたらしいので、それを使ってみるのも手。ただし、Xtionの座標が合っているのか、ps4eyeと競合しないか、などは@Horisu に任せます。
なお、Kinectは今肩についていますが、そのうち腰位置で360度Aeroのまわりを回転移動するようになる予定です。
ということで、本題の使い方ですが
ロボットPCでroslaunch aero_application kinect_rgbd.launch
してから、
Windows側(Vaio)でaero-ros-pkg/aero_application/aero_kinect/windows/KinectSimpleRgbdServer/KinectSimpleRgbdServer/bin/Debug/KinectSimpleRgbdServer.exe
をダブルクリックで起動する。すると黒い端末が出てくるのでエンターキーを押す。
これで通信プログラムが始まり、点群を取ってきたり画像を取ってきたりできます。
使い方はROSのサービスを呼ぶと、点群を一回だけ取ってきたり、画像を一回だけ取ってきたり、点群をストリーミングさせたり、画像をストリーミングさせたり、ができます。
それぞれサンプルコマンドがaero_application/aero_kinect/linux/KinectSimpleRgbdClient/examples
に置いてあります。
この他にも、物理座標系をデプス座標系、カラー座標系のピクセル座標として変換したり、画像の指定範囲に識別をかけたり、といった機能も存在いますが、サンプル実装が追いついていない。。。
ストリーミングの止め方は、他のコマンドで上書くこと。それと、たまにROSのサービスを呼んだのに返事が数秒たっても返ってこないということがありますが、これに遭遇したときは、両方の通信プログラムを再起動して試してください。一回目の通信がうまく行けばだいたいあとは問題なくうまく行っている気がします。
When running create_urdf.sh if you have a mesh file name that contains a joint name as a substring,
that is, e.g.:
Joint name : J1
Link name : J1_LINK
Link mesh file name : :J1_LINK_MESH.wrl
this part of create_urdf.sh
elif [[ $type == "joint" ]]
then
sed -i "/mesh/! s/$input_name/$output_name/g" /tmp/$1_tmp
echo "${output_name}" >> $save_tmp_to
fi
will accidentally rename the mesh file name as well.
This causes the robot to not be displayed properly in rviz.
調査した関節:l_shoulder_p, l_shoulder_r, l_elbow, l_wrist_p, l_wrist_r, waist_p, waist_r
中でもl_wrist_rが全体的に返り値がおかしいです。
以下該当指令と誤差です(誤差はラジアン)
なお、誤差が大きい基準は0.02より差が大きかった場合(通常0.002以内に収まる)
動きがおかしい
[ WARN] [1490009926.500173766]: bad diff in l_shoulder_p_joint -1.570800: 1.570800
返信誤差が大きい
[ WARN] [1490009928.152225003]: bad diff in l_shoulder_p_joint -1.553350: 0.709309
[ WARN] [1490011447.359651583]: bad diff in l_shoulder_r_joint 1.570500: 0.027977
l_wrist_r全体的におかしいので全掲載
[ WARN] [1490011615.687699500]: bad diff in l_wrist_r_joint -0.698132: 0.179880
[ WARN] [1490011617.341901127]: bad diff in l_wrist_r_joint -0.680682: 0.181031
[ WARN] [1490011618.985043812]: bad diff in l_wrist_r_joint -0.663232: 0.182564
[ WARN] [1490011620.623448896]: bad diff in l_wrist_r_joint -0.645782: 0.183825
[ WARN] [1490011622.281914755]: bad diff in l_wrist_r_joint -0.628332: 0.185279
[ WARN] [1490011623.937390455]: bad diff in l_wrist_r_joint -0.610882: 0.187690
[ WARN] [1490011625.590775751]: bad diff in l_wrist_r_joint -0.593432: 0.209061
[ WARN] [1490011627.225210333]: bad diff in l_wrist_r_joint -0.575982: 0.175653
[ WARN] [1490011628.868480917]: bad diff in l_wrist_r_joint -0.558532: 0.177970
[ WARN] [1490011630.519818515]: bad diff in l_wrist_r_joint -0.541082: 0.179550
[ WARN] [1490011632.177171277]: bad diff in l_wrist_r_joint -0.523632: 0.181889
[ WARN] [1490011633.815170070]: bad diff in l_wrist_r_joint -0.506182: 0.184299
[ WARN] [1490011635.468098330]: bad diff in l_wrist_r_joint -0.488732: 0.187713
[ WARN] [1490011637.125480085]: bad diff in l_wrist_r_joint -0.471282: 0.190124
[ WARN] [1490011638.763329146]: bad diff in l_wrist_r_joint -0.453832: 0.158631
[ WARN] [1490011640.420147466]: bad diff in l_wrist_r_joint -0.436382: 0.162044
[ WARN] [1490011642.071022362]: bad diff in l_wrist_r_joint -0.418932: 0.165304
[ WARN] [1490011643.727754018]: bad diff in l_wrist_r_joint -0.401482: 0.169646
[ WARN] [1490011645.398588906]: bad diff in l_wrist_r_joint -0.384032: 0.172978
[ WARN] [1490011647.052636896]: bad diff in l_wrist_r_joint -0.366582: 0.142413
[ WARN] [1490011648.710351130]: bad diff in l_wrist_r_joint -0.349132: 0.146593
[ WARN] [1490011650.368080821]: bad diff in l_wrist_r_joint -0.331682: 0.151873
[ WARN] [1490011652.022409991]: bad diff in l_wrist_r_joint -0.314232: 0.156030
[ WARN] [1490011653.679874602]: bad diff in l_wrist_r_joint -0.296782: 0.126332
[ WARN] [1490011655.335690766]: bad diff in l_wrist_r_joint -0.279332: 0.131390
[ WARN] [1490011656.986368157]: bad diff in l_wrist_r_joint -0.261882: 0.137553
[ WARN] [1490011658.618215683]: bad diff in l_wrist_r_joint -0.244432: 0.108810
[ WARN] [1490011660.272186548]: bad diff in l_wrist_r_joint -0.226982: 0.759479
[ WARN] [1490011661.927832588]: bad diff in l_wrist_r_joint -0.209532: 0.121026
[ WARN] [1490011663.583337709]: bad diff in l_wrist_r_joint -0.192082: 0.093249
[ WARN] [1490011665.235112515]: bad diff in l_wrist_r_joint -0.174632: 0.100248
[ WARN] [1490011666.889431854]: bad diff in l_wrist_r_joint -0.157182: 0.072409
[ WARN] [1490011668.542972200]: bad diff in l_wrist_r_joint -0.139732: 0.080370
[ WARN] [1490011670.196710338]: bad diff in l_wrist_r_joint -0.122282: 0.053514
[ WARN] [1490011671.852724668]: bad diff in l_wrist_r_joint -0.104832: 0.061409
[ WARN] [1490011673.497078337]: bad diff in l_wrist_r_joint -0.087382: 0.035548
[ WARN] [1490011675.132554692]: bad diff in l_wrist_r_joint -0.069932: 0.044593
[ INFO] [1490011676.786259419]: diff okay in l_wrist_r_joint -0.052482: 0.018732
[ WARN] [1490011678.439260780]: bad diff in l_wrist_r_joint -0.035032: 0.065628
[ WARN] [1490011680.097195540]: bad diff in l_wrist_r_joint -0.017582: 0.040818
[ WARN] [1490011681.767852388]: bad diff in l_wrist_r_joint -0.000132: 0.050915
[ INFO] [1490011683.421663238]: diff okay in l_wrist_r_joint 0.017318: 0.011175
[ INFO] [1490011685.067334215]: diff okay in l_wrist_r_joint 0.034768: 0.012583
[ INFO] [1490011686.698897458]: diff okay in l_wrist_r_joint 0.052218: 0.002487
[ WARN] [1490011688.343827503]: bad diff in l_wrist_r_joint 0.069668: 0.028348
[ INFO] [1490011690.002903914]: diff okay in l_wrist_r_joint 0.087118: 0.019395
[ WARN] [1490011691.641119506]: bad diff in l_wrist_r_joint 0.104568: 0.045206
[ WARN] [1490011693.295813726]: bad diff in l_wrist_r_joint 0.122018: 0.037245
[ WARN] [1490011694.946748785]: bad diff in l_wrist_r_joint 0.139468: 0.064045
[ WARN] [1490011696.602103725]: bad diff in l_wrist_r_joint 0.156918: 0.056019
[ WARN] [1490011698.235394882]: bad diff in l_wrist_r_joint 0.174368: 0.082764
[ WARN] [1490011699.869072006]: bad diff in l_wrist_r_joint 0.191818: 0.719751
[ WARN] [1490011701.524094688]: bad diff in l_wrist_r_joint 0.209268: 0.748609
[ WARN] [1490011703.179183578]: bad diff in l_wrist_r_joint 0.226718: 0.097256
[ WARN] [1490011704.812376360]: bad diff in l_wrist_r_joint 0.244168: 0.091092
[ WARN] [1490011706.464632349]: bad diff in l_wrist_r_joint 0.261618: 0.119836
[ WARN] [1490011708.116301655]: bad diff in l_wrist_r_joint 0.279068: 0.113721
[ WARN] [1490011709.753251310]: bad diff in l_wrist_r_joint 0.296518: 0.108591
[ WARN] [1490011711.407753054]: bad diff in l_wrist_r_joint 0.313968: 0.138217
[ WARN] [1490011713.065520544]: bad diff in l_wrist_r_joint 0.331418: 0.132937
[ WARN] [1490011714.717124591]: bad diff in l_wrist_r_joint 0.348868: 0.127726
[ WARN] [1490011716.372533951]: bad diff in l_wrist_r_joint 0.366318: 0.123384
[ WARN] [1490011718.019726615]: bad diff in l_wrist_r_joint 0.383768: 0.153949
[ WARN] [1490011719.677561532]: bad diff in l_wrist_r_joint 0.401218: 0.149608
[ WARN] [1490011721.336657836]: bad diff in l_wrist_r_joint 0.418668: 0.146336
[ WARN] [1490011722.991386607]: bad diff in l_wrist_r_joint 0.436118: 0.141920
[ WARN] [1490011724.625883207]: bad diff in l_wrist_r_joint 0.453568: 0.173412
[ WARN] [1490011726.281929261]: bad diff in l_wrist_r_joint 0.471018: 0.169999
[ WARN] [1490011727.933709508]: bad diff in l_wrist_r_joint 0.488468: 0.167588
[ WARN] [1490011729.581401785]: bad diff in l_wrist_r_joint 0.505918: 0.164174
[ WARN] [1490011731.232369051]: bad diff in l_wrist_r_joint 0.523368: 0.161835
[ WARN] [1490011732.888757879]: bad diff in l_wrist_r_joint 0.540818: 0.159253
[ WARN] [1490011734.543128411]: bad diff in l_wrist_r_joint 0.558268: 0.191749
[ WARN] [1490011736.195977995]: bad diff in l_wrist_r_joint 0.575718: 0.189352
[ WARN] [1490011737.858900090]: bad diff in l_wrist_r_joint 0.593168: 0.186827
[ WARN] [1490011739.510772996]: bad diff in l_wrist_r_joint 0.610618: 0.185420
[ WARN] [1490011741.147152782]: bad diff in l_wrist_r_joint 0.628068: 0.184012
[ WARN] [1490011742.782575468]: bad diff in l_wrist_r_joint 0.645518: 0.182552
[ WARN] [1490011744.437782385]: bad diff in l_wrist_r_joint 0.662968: 0.181297
[ WARN] [1490011746.089681017]: bad diff in l_wrist_r_joint 0.680418: 0.179752
[ WARN] [1490011747.761286571]: bad diff in l_wrist_r_joint 0.697868: 0.178607
すでに他のシステムでは実装できているという情報を聞きました.
こちらにできないはずはないので,すこし試してみます.
前の指令が実行され終わる前に次の指令を送ると上書きされることを確認しました.
終わっているかどうかを判定してwaitするだけでできるはずです.
という問題が昨日からあって(というより今まで返ってくる角度をあまりちゃんと見ていなくて気づいていなかっただけかもしれませんが)、調べてみると
ストローク列送信コマンドをセット>値読み取り>現在値取得コマンドをセット>値読み取り>脱調監視コマンドをセット>値読み取り>現在値取得コマンドをセット>値読み取り
と送ったときに、get_dataが
ストローク列送信コマンドをセット>値読み取り(送信コマンド時の現在値)>現在値取得コマンドをセット>値読み取り(送信コマンド時の現在値)>脱調監視コマンドをセット>値読み取り(現在値取得時の現在値)>現在値取得コマンドをセット>値読み取り(脱調監視の結果)
と一個ずつ取得しているバッファ(?)がずれ出していたのが原因で、コマンドをセットする前にflushを入れたところ、この問題については解決しましたが、ストローク列送信コマンドを送ったあとに取得する現在値にたまにストローク0が入ってしまい、角度値がおかしなことになっています。
現在値取得コマンドからの現在値はおおよそ正しい(こちらも極稀に0が紛れ込みますが)
ということで、困っています。
(補間なしモードで運用すれば、送信コマンドの現在値を使わなくてすむので、上記問題はひとまず回避できます)
after installation and running roseus aero-interface.l
I get following errors:
/opt/ros/indigo/share/euslisp/jskeus/eus/Linux64/bin/irteusgl: ERROR th=0 unbound variable gl::glbodygl::glbody in (make-class 'collada-body :super gl::glbody :slots '(glvertices) :metaclass nil :element-type nil :size -1 :documentation nil)E:
cppバインディング上で起きた事象ですが,
引数を330.0, 0.0, 0.0とするべきところを
330.0, 0.0, 10.0としたところgoposが止まらなくなりました
ロボットモデルが増えてきているのと、今までの運用でいくつか問題点があったので、以下、今後の修正として上げたい項目です:
aero-interface.lを読み込んでaero-initを呼ぶと、/default_robot_interface~が/joint_statesにひたすら全関節0の値を出し続けます。これをmoveitが読み込んでしまうと動かなくなります。
neck_pをmax_angleに設定して、
send *aero* :head :neck_p :joint-angle 40
send *ri* :angle-vector (send *aero* :angle-vector) 5000
その後ungrasp,graspを繰り返すと頭が下を向いていく(neck_pがmax_angleを超えて大きくなっている?)のが確認されました。
角度を確認したところ
send *ri* :state
send *aero* :angle-vector (send *ri* :actual-vector)
send *aero* :head :neck_p :joint-angle
では、首が下がっていっても40と表示されました。
neck_pを39にしたところこの問題は起きなかったので、取り敢えずaero-interface.lに書かれているmax_angleを39にしておいて後で検証するのが良いかと思います。
when following the install instructions and executing ./setup.sh aero_wheels, the following error arises:
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_controller_manager/AeroHandController.cc:8:45: fatal error: aero_startup/AeroHandController.h: No such file or directory
#include <aero_startup/AeroHandController.h>
(terminal output copied below)
However, after executing catkin build aero_startup, then executing ./setup.sh aero_wheels again the error went away.
The same phenomenon appeared on two machines (both ubuntu 14.04 indigo).
========= terminal output ===========
Extending: [cached] /home/wesleyc/ros/indigo_parent/devel:/opt/ros/indigo
Source Space: [exists] /home/wesleyc/ros/indigo/src
Log Space: [exists] /home/wesleyc/ros/indigo/logs
Build Space: [exists] /home/wesleyc/ros/indigo/build
Devel Space: [exists] /home/wesleyc/ros/indigo/devel
Install Space: [unused] /home/wesleyc/ros/indigo/install
Devel Space Layout: linked
Additional CMake Args: None
Additional Make Args: None
Additional catkin Make Args: None
Internal Make Job Server: True
Whitelisted Packages: None
WARNING: Your current environment's CMAKE_PREFIX_PATH is different from the
cached CMAKE_PREFIX_PATH used the last time this workspace was built.
If you want to use a different CMAKE_PREFIX_PATH you should call catkin clean
to remove all references to the previous CMAKE_PREFIX_PATH.
Cached CMAKE_PREFIX_PATH:
/home/wesleyc/ros/indigo_parent/devel:/opt/ros/indigo
Current CMAKE_PREFIX_PATH:
[build] Found '297' packages in 0.0 seconds.
[build] Package table is up to date.
Starting >>> assimp_devel
Starting >>> openrtm_tools
Starting >>> rtmbuild
Finished <<< rtmbuild [ 0.3 seconds ]
Finished <<< openrtm_tools [ 0.2 seconds ]
Starting >>> hrpsys_tools
Finished <<< assimp_devel [ 0.2 seconds ]
Starting >>> euscollada
Finished <<< hrpsys_tools [ 0.2 seconds ]
Finished <<< euscollada [ 0.1 seconds ]
Starting >>> hrpsys_ros_bridge
Warnings << hrpsys_ros_bridge:symlink /home/wesleyc/ros/indigo/logs/hrpsys_ros_bridge/build.symlink.009.log
Warning: Cannot symlink from /home/wesleyc/ros/indigo/devel/.private/hrpsys_ros_bridge/share/roseus/ros/diagnostic_msgs/manifest.l to existing file /home/wesleyc/ros/indigo/devel/share/roseus/ros/diagnostic_msgs/manifest.l
Warning: Source hash: 096f24144dbc77e3a7be41996f909a49
Warning: Dest hash: 23a31241cf67b30b2fdd5c4eb1700bcc
Warning: Cannot symlink from /home/wesleyc/ros/indigo/devel/.private/hrpsys_ros_bridge/share/roseus/ros/nav_msgs/manifest.l to existing file /home/wesleyc/ros/indigo/devel/share/roseus/ros/nav_msgs/manifest.l
Warning: Source hash: 8454533a70a1df1f667e36d7e0e45bf0
Warning: Dest hash: 5391ce1a3737f4825944a6e88956c4b1
Warning: Cannot symlink from /home/wesleyc/ros/indigo/devel/.private/hrpsys_ros_bridge/share/roseus/ros/shape_msgs/manifest.l to existing file /home/wesleyc/ros/indigo/devel/share/roseus/ros/shape_msgs/manifest.l
Warning: Source hash: bfc76431cefec9264b1eb5b5698255e0
Warning: Dest hash: 9cb71f48c3097b437ca90ae95b74824d
Warning: Cannot symlink from /home/wesleyc/ros/indigo/devel/.private/hrpsys_ros_bridge/share/roseus/ros/pr2_controllers_msgs/manifest.l to existing file /home/wesleyc/ros/indigo/devel/share/roseus/ros/pr2_controllers_msgs/manifest.l
Warning: Source hash: 06e24a0d9319ad0a00528a7f31438f1c
Warning: Dest hash: ef5a7f9c2db178f0a22bf0158d634741
Warning: Cannot symlink from /home/wesleyc/ros/indigo/devel/.private/hrpsys_ros_bridge/share/roseus/ros/trajectory_msgs/manifest.l to existing file /home/wesleyc/ros/indigo/devel/share/roseus/ros/trajectory_msgs/manifest.l
Warning: Source hash: 104ade077cda36db1cfaceb265bf3c13
Warning: Dest hash: b3150658413661561aeb6b8cafbc118a
Warning: Cannot symlink from /home/wesleyc/ros/indigo/devel/.private/hrpsys_ros_bridge/share/roseus/ros/bond/manifest.l to existing file /home/wesleyc/ros/indigo/devel/share/roseus/ros/bond/manifest.l
Warning: Source hash: e9ce6b978f10bc9d4230cc4945cb307a
Warning: Dest hash: 66dbfcb99b7da0c6c489f15fa5056db5
Warning: Cannot symlink from /home/wesleyc/ros/indigo/devel/.private/hrpsys_ros_bridge/share/roseus/ros/pr2_msgs/manifest.l to existing file /home/wesleyc/ros/indigo/devel/share/roseus/ros/pr2_msgs/manifest.l
Warning: Source hash: 53e37dc48aaee01bc8c2da721469ae86
Warning: Dest hash: 0c3729cc2d318c638d0ca2f81bc3acc6
Warning: Cannot symlink from /home/wesleyc/ros/indigo/devel/.private/hrpsys_ros_bridge/share/roseus/ros/control_msgs/manifest.l to existing file /home/wesleyc/ros/indigo/devel/share/roseus/ros/control_msgs/manifest.l
Warning: Source hash: b3f32d5e57c05c67fa33f2691c23659d
Warning: Dest hash: dabfbb494e8843c4bb9b3e50860915ff
...............................................................................
Finished <<< hrpsys_ros_bridge [ 6.8 seconds ]
Starting >>> aero_startup
Errors << aero_startup:make /home/wesleyc/ros/indigo/logs/aero_startup/build.make.003.log
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_controller_manager/AeroHandController.cc:8:45: fatal error: aero_startup/AeroHandController.h: No such file or directory
#include <aero_startup/AeroHandController.h>
^
compilation terminated.
make[2]: *** [CMakeFiles/aero_hand_controller_node.dir/aero_controller_manager/AeroHandController.cc.o] Error 1
make[1]: *** [CMakeFiles/aero_hand_controller_node.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc: In member function ‘aero::navigation::pose aero::navigation::AeroMoveBase::dX(std::vector, float)’:
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘- _vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator >(0ul)’ from ‘__gnu_cxx::__alloc_traitsstd::allocator::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
{-_vels[0], _vels[1], -_vels[2], _vels[3]};
^
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘- _vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator >(0ul)’ from ‘__gnu_cxx::__alloc_traitsstd::allocator::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘_vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator >(1ul)’ from ‘__gnu_cxx::__alloc_traitsstd::allocator::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘_vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator >(1ul)’ from ‘__gnu_cxx::__alloc_traitsstd::allocator::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘- _vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator >(2ul)’ from ‘__gnu_cxx::__alloc_traitsstd::allocator::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘- _vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator >(2ul)’ from ‘__gnu_cxx::__alloc_traitsstd::allocator::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘_vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator >(3ul)’ from ‘__gnu_cxx::__alloc_traitsstd::allocator::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:67:48: warning: narrowing conversion of ‘_vels.std::vector<_Tp, _Alloc>::operator[]<double, std::allocator >(3ul)’ from ‘__gnu_cxx::__alloc_traitsstd::allocator::value_type {aka double}’ to ‘float’ inside { } [-Wnarrowing]
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:76:32: warning: narrowing conversion of ‘(((((double)(Vx * 2.0e+0f)) * 3.1415926535897931e+0) * 7.5999997556209564e-2) * ((double)_dt))’ from ‘double’ to ‘float’ inside { } [-Wnarrowing]
return {Vx * 2_M_PI * radius * _dt,
^
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:77:30: warning: narrowing conversion of ‘(((((double)(Vy * 2.0e+0f)) * 3.1415926535897931e+0) * 7.5999997556209564e-2) * ((double)_dt))’ from ‘double’ to ‘float’ inside { } [-Wnarrowing]
Vy * 2_M_PI * radius * _dt,
^
/home/wesleyc/ros/indigo/src/aero-ros-pkg-prerelease/aero_startup/aero_move_base/AeroBaseController.cc:78:44: warning: narrowing conversion of ‘((((double)_dt) * 3.5814155801515208e+0) / 1.2619882914178727e+2)’ from ‘double’ to ‘float’ inside { } [-Wnarrowing]
max_velocity * radius * M_PI * _dt / (sqrt(2) * Radius * 300)};
^
make: *** [all] Error 2
cd /home/wesleyc/ros/indigo/build/aero_startup; catkin build --get-env aero_startup | catkin env -si /usr/bin/make --jobserver-fds=6,7 -j; cd -
...............................................................................
Failed << aero_startup:make [ Exited with code 2 ]
Failed <<< aero_startup [ 20.7 seconds ]
[build] Summary: 6 of 7 packages succeeded.
[build] Ignored: 290 packages were skipped or are blacklisted.
[build] Warnings: 1 packages succeeded with warnings.
[build] Abandoned: None.
[build] Failed: 1 packages failed.
[build] Runtime: 30.4 seconds total.
finished.
Because there was a big change in the models directory, there will be a change in how to generate the eus model from wrl.
This is in development.
roscd aero_description/scripts
./gen_from_wrl.sh aero_four_legs
cp ../aero_four_legs/models/gen/aero_upper.l ../aero_wheels_typeC/models/gen/aero_upper.l
cp ../aero_four_legs/models/urdf/aero_upper.urdf ../aero_wheels_typeC/models/urdf/aero_upper.urdf
roscd aero_description
./setup.sh --local aero_wheels_typeC
[update]
All duplicates of aero_upper.l should load from aero_four_legs/models/gen/aero_upper.l
This way, we don't have to go through the cps, and we can easily run ./setup.sh after ./gen_from_wrl.sh.
For the urdf, we can create a reference dummy file instead.
@wesleypchan @chibi314 SingleArmの統合を行いましょう.
there will be a major update around controllers in the coming week.
updates include
tests have been conducted with aero_wheels
we are not sure how this update will influence other robots, so please create backups of your current working directory
Aero armで
roslaunch aero_startup aero_bringup.launch
roseus aero-arm-single-wrist-interface.l
をして
aero-init
load-controllers
objects (list *aero*)
send *ri* :go-pos 0 0 0
とすると以下のようにエラーが出ます。解決方法を教えていただきたいです。
/home/leus/ros/indigo_parent/devel/share/euslisp/jskeus/eus/Linux64/bin/irteusg\ l 0 error: unbound variable base-coords in (send base-coords :translate (float-\ vector x y 0))
ハードウェア構成が若干変更になっており,
ロボットPCとクライアントをアップデートする必要があります.
aero_wheels_typeCの台車に変更になりました.
リフターはaero_wheelsの状態なので,
aero_wheels_typeCの下のAeroBaseControllerを移植する必要があります.
その前にtypeCで入ったdiffをコミットかな?
A declarative, efficient, and flexible JavaScript library for building user interfaces.
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
An Open Source Machine Learning Framework for Everyone
The Web framework for perfectionists with deadlines.
A PHP framework for web artisans
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
Some thing interesting about web. New door for the world.
A server is a program made to process requests and deliver data to clients.
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
Some thing interesting about visualization, use data art
Some thing interesting about game, make everyone happy.
We are working to build community through open source technology. NB: members must have two-factor auth.
Open source projects and samples from Microsoft.
Google ❤️ Open Source for everyone.
Alibaba Open Source for everyone
Data-Driven Documents codes.
China tencent open source team.