Ben and David,
robot_state_publisher does not have persistence currently because if you have persistence you must have policies about how long to persist things before erroring etc.  These persistence models are very robot and application specific. 

If you need persistence for a specific application it actually makes sense to keep that knowledge outside of the robot state publisher in something like David's aggregator. 

in general republishing old data is not very good thing to do.  That information has already been sent out and has been recorded in tf buffers around the system. 

One thing which I think might help your use cases is to allow publishing of partial trees not starting at the root.  Such that if you provide data about M of N  links it will publish data about the M links even if they are disjoint and skip the remaining links.

Would this handle your use cases?
Tully

On Fri, Oct 1, 2010 at 6:35 AM, David Lu!! <davidvlu@gmail.com> wrote:
This is a problem I've run into as well. The way I usually fix it is
to write a node that aggregates the joint state messages and send out
a new stream with all the joints. But I agree, robot_state_publisher's
lack of memory is a problem sometimes.
-DL!!

On Fri, Oct 1, 2010 at 8:07 AM, Axelrod, Benjamin <baxelrod@irobot.com> wrote:
> I am using the robot_state_publisher to convert my joint angles to tf
> transforms.  However, it seems that the robot_state_publisher doesn’t like
> it when you send it different joints at different times.  In other words,
> robot_state_publisher doesn’t maintain any state…
>
>
>
> For example, my urdf has 2 joints:
>
> Base -> joint1 -> link1 -> joint2 -> link2
>
>
>
> If I send it joint1, then at a later time I send it joint 2, I get this
> error:
>
>
>
> Node: /robot_state_publisher
>
> Time: 1285876513.251897000
>
> Severity: Error
>
> Location:
> /home/arm_user/darpa_arm_software/stacks/robot_model/robot_state_publisher/src/robot_state_publisher.cpp:RobotStatePublisher::publishTransforms:78
>
> Published Topics: /rosout, /tf
>
> Could not compute link poses. The tree or the state is invalid.
>
>
>
> But if I send both joints at once, then everything is fine.  This seems like
> a major limitation to me.  Am I missing something?
>
>
>
> I am using boxturtle.  And am using robot_state_publisher running as a node.
>
>
>
> Thanks,
>
> -Ben
>
>
>
> Ben Axelrod
>
> Research Scientist
>
> iRobot Corporation
>
> 8 Crosby Drive, Mail Stop 8-1
>
> Bedford, MA 01730
>
> (781) 430-3315 (Tel)
>
> (781) 960-2628 (Fax)
>
> baxelrod@irobot.com
>
>
>
> _______________________________________________
> ros-users mailing list
> ros-users@code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
>
_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users



--
Tully Foote
Systems Engineer
Willow Garage, Inc.
tfoote@willowgarage.com
(650) 475-2827