ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

set tf_remap private parameters from console

asked 2011-11-09 09:25:42 -0500

updated 2011-11-14 03:51:30 -0500

Hi!! I'm trying to use the tf_remap node without making a launch file. The problem is that the mapping should be specified in the ~mappings parameter of the tf_remap node. I tried this but it does not work:

$ rosparam set /tf_remap/~mappings "[{/neck_2: /neck_1}, {/left_shoulder_2: /left_shoulder_1}, {/left_elbow_2: /left_elbow_1}]"
$ rosparam get /tf_remap/~mappings
- {/neck_2: /neck_1}
- {/left_shoulder_2: /left_shoulder_1}
- {/left_elbow_2: /left_elbow_1}
$ rosrun tf tf_remap __name:=tf_remap
Applying the following mappings to incoming tf frame ids {}

I've studied the ros name convention and everything seems fine from my point of view. Any Idea?


EDITED after the bhaskara suggestion:

I also tested the below example and it does not work:

$ rosparam get /tf_remap/mappings
- {/neck_2: /neck_1}
- {/left_shoulder_2: /left_shoulder_1}
- {/left_elbow_2: /left_elbow_1}

$ rosrun tf tf_remap __name:=tf_remap
Applying the following mappings to incoming tf frame ids {}

EDITED: Third attempt:

$ rosbag play gesture_recording.bag tf:=tf_old &

#brute force:
$ rosparam set mappings "[{old: /neck_2,new: /neck_1}]"
$ rosparam set /mappings "[{old: /neck_2,new: /neck_1}]"
$ rosparam set tf_remap/mappings "[{old: /neck_2,new: /neck_1}]"
$ rosparam set /tf_remap/mappings "[{old: /neck_2,new: /neck_1}]"

$ rosrun tf tf_remap &
Applying the following mappings to incoming tf frame ids {}
$ rostopic echo /tf

> [...]
> -- transforms: 
>   - 
>     header: 
>       seq: 0
>       stamp: 
>         secs: 1320600273
>         nsecs: 859003197
>       frame_id: /openni_depth_frame
>     child_frame_id: /neck_2
>     transform: 
>       translation: 
>         x: 1.68099461393
>         y: -0.25899046843
>         z: 0.235416310719
>       rotation: 
>         x: 0.279471530986
>         y: 0.53708064566
>         z: 0.633364982269
>         w: 0.481963528351
> --- transforms:  
> [...]

Also tested with the same results:

rosrun tf tf_remap _mappings:='{old: /neck_2, new: /neck_1}' 
edit retag flag offensive close merge delete

3 Answers

Sort by » oldest newest most voted
4

answered 2011-12-04 02:01:58 -0500

sergey_alexandrov gravatar image

I have recently come across the same problem. I continued your brute-force and found a working command:

rosrun tf tf_remap _mappings:='[{old: /neck_2, new: /neck_1}]' 
Applying the following mappings to incoming tf frame ids {'/neck_2': '/neck_1'}
edit flag offensive delete link more

Comments

It worked :-)
Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2011-12-04 07:03:38 -0500 )edit

Remember to play the bag with rosbag play x.bag /tf:=/tf_old (Thanks to @Ben_S)

Benoit Larochelle gravatar image Benoit Larochelle  ( 2013-03-04 00:37:51 -0500 )edit
2

answered 2011-11-09 10:23:30 -0500

bhaskara gravatar image

You don't need the ~: just do 'rosparam set /tf_echo/mappings'. '~' is not used when the name is already fully qualified (starts with '/').

edit flag offensive delete link more

Comments

I tried also that and does not work:
Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2011-11-09 19:46:26 -0500 )edit
The parameter value is also incorrect. Try something like 'rosparam set /tf_remap/mappings "[{old: /neck_2, new: /neck_1}]"'.
bhaskara gravatar image bhaskara  ( 2011-11-10 05:57:10 -0500 )edit
which parameter is also incorrect? I tried what you say (see edited comment) :-) I don't understand what do you mean. thanks for the interest :-)
Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2011-11-10 07:48:13 -0500 )edit
Your edited comment doesn't match what I typed. Look carefully :)
bhaskara gravatar image bhaskara  ( 2011-11-10 10:32:27 -0500 )edit
certainly bhaskara. I also tried your suggestion in a third attempt (edited post) with the same results. It is strange, your suggestion seems to be absolutely coherent with the remap documentation: ~mappings ([ {str: str} ], default: []) 'each dictionary in the list must have an "old" and "new" key'
Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2011-11-14 03:48:05 -0500 )edit
Each of those is subtly wrong in a different way :) the first one needs to set the node name as you were doing earlier with '__name:=tf_remap'. The second one needs to enclose the map in a vector, i.e. [{old: /neck_2, ...}] (note the square brackets).
bhaskara gravatar image bhaskara  ( 2011-11-14 05:57:02 -0500 )edit
0

answered 2011-11-09 20:31:12 -0500

dornhege gravatar image

I think it works, but the printout might be misleading. I tried:

rosrun tf tf_remap _mappings:='{bla:/blubb}'
ERROR: Invalid remapping argument '_mappings:={bla:/blubb}'
Applying the following mappings to incoming tf frame ids {}

and then fixed the missing space:

rosrun tf tf_remap _mappings:='{bla: /blubb}'
Applying the following mappings to incoming tf frame ids {}

So, I think the parameter setting arrived. Maybe the printout says what mappings were actually applied and thus is quiet without data?

edit flag offensive delete link more

Comments

No luck with your method too. I edited the post with the results. I'm not sure what I'm doing wrong yet.
Pablo Iñigo Blasco gravatar image Pablo Iñigo Blasco  ( 2011-11-14 03:50:42 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2011-11-09 09:25:42 -0500

Seen: 2,240 times

Last updated: Dec 04 '11