[orocosusers] Dynamic port type

Dear Orocos users,

In order to make a component as general as possible I decided to make a
property which would give the possibility to choose the port type e.g.
choose between KDL::Twist, std::vector, geometry_msgs:Twist.

- So my first question is, what is the best way of doing this? Would you
even recommend it?

- The second question is about how I implemented it:

in hpp:*
*

*typedef RTT::InputPort< KDL::Twist > PortType_IN_KDL;**
**typedef RTT::InputPort< geometry_msgs::Twist > PortType_IN_GEO;**
**typedef RTT::InputPort< std::vector<double> > PortType_IN_VEC;*

*boost::shared_ptr< PortType_IN_VEC > vel_vec_inport_;**
**boost::shared_ptr< PortType_IN_GEO > vel_geo_inport_;**
**boost::shared_ptr< PortType_IN_KDL > vel_kdl_inport_;*

and then in configureHook in cpp did this for each:

vel_vec_inport_ = boost::make_shared< CartPortType_IN_VEC>();
this->addPort("vel_vec_inport",*vel_vec_inport_).doc("velocity inport in
std::vector format");

The problem is that once I start the component, stopping it will cause
problem. Either for orocos or for the component itself...

Inside deployer if I call component.stop and then component.cleanup it
doesn't complain. But if I now call 'configure', it goes to the famous
error "pure virtual method called, terminate called without an active
exception"... I also tried to reset the shared pointer with

vel_vec_inport_.reset()

But that doesn't seem to help. I tried calling
this->removePort(vel_vec_inport_) in cleanup, but that doesn't even
compile...

If once the component has started, I exit deployer I get the error:

*terminate called after throwing an instance of
'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector >'**
** what(): boost: mutex lock failed in pthread_mutex_lock: Invalid
argument**
**/opt/ros/indigo/lib/rtt_ros/deployer: line 5: 24934
Aborted (core dumped) deployer "$@"*

I would appreciate if you have any idea why things go wrong here...

Thanks

Cheers

Keivan

[orocosusers] Dynamic port type

Hi Keivan,

On Fri, Nov 25, 2016 at 11:07 AM, Keivan Zavari <keivan [dot] zavari [..] ...>
wrote:

> Dear Orocos users,
>
> In order to make a component as general as possible I decided to make a
> property which would give the possibility to choose the port type e.g.
> choose between KDL::Twist, std::vector, geometry_msgs:Twist.
>
> - So my first question is, what is the best way of doing this? Would you
> even recommend it?
>

Willy already elaborated on this part and I agree with his suggestion 2.
With the current feature set of RTT your approach is also fine if you
really need to support all three types and simply adding all three to the
component interface and connecting only one is not an option. It should be
noted that adding ports in configureHook() is possible, but it breaks some
standard deployer functions like configureComponents()
<https://github.com/orocos-toolchain/ocl/blob/master/deployment/DeploymentComponent.cpp#L1234>
because
they try to connect ports before configuring the components. The "dynamic"
ports can therefore not be connected by the deployer, at least not within
the same group/deployment configuration file. Not a big issue if you have a
custom deployment script or a simple executable which deploys your
application.

There are various options how Orocos RTT could be improved to better
support your use case. For example, it could allow connections between
ports of different types if the respective typekits or the user register a
constructor to convert samples between the two. The constructor concept is
already implemented in the RTT type system and mainly used for scripting,
so why not also for port connections? It needs to be verified if the
conversion could be done without having to give up real-time guarantees
either for the write or read operation.Another option is a kind of
connector concept as outlined by Willy.

For ROS users there is another solution we are already actively working on,
which is actually quite simple. If it is only for connecting publishers and
subscribers to standard Orocos components that know nothing about ROS and
have ports with simple or KDL types, we can provide a ROS transport for
these that translates between the "native" type and a compatible ROS
common_msgs type, e.g. double<->std_msgs/Float64, string<->std_msgs/String
or KDL::Twist<->geometry_msgs/Twist. In your case it would perhaps not be
necessary anymore to have a geometry_msgs::Twist port, because you could
simply connect the KDL::Twist port to a ROS publisher stream directly and
even reduce conversion overhead in most cases.

> - The second question is about how I implemented it:
>
> in hpp:
>
> *typedef RTT::InputPort< KDL::Twist > PortType_IN_KDL;*
> *typedef RTT::InputPort< geometry_msgs::Twist > PortType_IN_GEO;*
> *typedef RTT::InputPort< std::vector<double> > PortType_IN_VEC;*
>
> *boost::shared_ptr< PortType_IN_VEC > vel_vec_inport_;*
> *boost::shared_ptr< PortType_IN_GEO > vel_geo_inport_;*
> *boost::shared_ptr< PortType_IN_KDL > vel_kdl_inport_;*
>
> and then in configureHook in cpp did this for each:
>
> vel_vec_inport_ = boost::make_shared< CartPortType_IN_VEC>();
> this->addPort("vel_vec_inport",*vel_vec_inport_).doc("velocity inport in
> std::vector format");
>
>
> The problem is that once I start the component, stopping it will cause
> problem. Either for orocos or for the component itself...
>
> Inside deployer if I call component.stop and then component.cleanup it
> doesn't complain. But if I now call 'configure', it goes to the famous
> error "pure virtual method called, terminate called without an active
> exception"... I also tried to reset the shared pointer with
>
> vel_vec_inport_.reset()
>
> But that doesn't seem to help. I tried calling this->removePort(vel_vec_inport_)
> in cleanup, but that doesn't even compile...
>

I have not tested this, but think you indeed need to remove the port
explicitly from the component interface in the cleanupHook() before you are
allowed to destroy it. The component, or more precisely its
DataFlowInterface
<https://github.com/orocos-toolchain/rtt/blob/master/rtt/DataFlowInterface.hp

,
stored a pointer to the port object, which is dangling if the port
disappears. Adding another port with the same name would remove the old
pointer, but you seem to have different names for the three ports.

DataFlowInterface::removePort(name)
<https://github.com/orocos-toolchain/rtt/blob/master/rtt/DataFlowInterface.cpp#L163>
expects the port name as a string argument. Maybe a bit inconsistent given
that addPort(port) has a reference argument. Unlike many other methods
removePort() is not exposed directly in the TaskContext interface and you
have to get a pointer to the TaskContext's root Service which implements
the DataFlowInterface using provides():

*this->provides()->removePort(vel_vec_inport->getName());*
*vel_vec_inport_.reset()*

should do what you expected.

>
> If once the component has started, I exit deployer I get the error:
>
> *terminate called after throwing an instance of
> 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector > >'*
> * what(): boost: mutex lock failed in pthread_mutex_lock: Invalid
> argument*
> */opt/ros/indigo/lib/rtt_ros/deployer: line 5: 24934
> Aborted (core dumped) deployer "$@"*
>
> I would appreciate if you have any idea why things go wrong here...
>
> Thanks
>
> Cheers
>
> Keivan
>
>
>
Cheers,
Johannes

[orocosusers] Dynamic port type

Hi,

IMO there is a lack in Orocos : a "connector" feature that allows us to
connect different port types without have to write a component, that is the
opportunity to write a conversion callback. There may be some possibilities
as ros/orocos can talk with different data types, but I don't know what's
behing, and I'm quite sure you have to be an orocos expert to be able to do
this.

That said, the aswer (as always) is -- it depends on your needs and
tradeoffs--.

1/ If you need to change the type inside your component :

If it's acceptable to have the same type for all ports in the system, I
would use compilation configuration with a define taking a different value
upon user choice, as it's certainly a system wide choice, then only the
necessary code is compile/executed.It's the no overhead solution.

If you need something more dynamic, I'll do a decorator class. Either one
interface IGeneralType implemented by 3 decorators (for each type), either
one decorator that aggregates all the possible types with a "type"
attribute you can use to identify the type. You may use pointers or value
depending on your constraints for the aggregation ("no malloc at runtime"
rule will enforce the use of value, and then a big memory overhead).

2/ If you only need to provide a rich external interface :

you may just create 3 real ports, ensure that only one is connected, and
make a component method to identify/read the good one. Once again it may be
done in different manner :
* at compilation time (then you only have one port at a time on your
external interface). You can still provide 3 libraries with the 3 different
types
* with a property checked a configure/start
* at run time with myport.connected() questions.

All is about overheads and tradeoffs.

My suggestion is to be in the 2/ case and stay modest with something not
too dynamic. The generalization effort should never be higher than the
source duplication maintenance...

2016-11-25 11:07 GMT+01:00 Keivan Zavari <keivan [dot] zavari [..] ...>:

> Dear Orocos users,
>
> In order to make a component as general as possible I decided to make a
> property which would give the possibility to choose the port type e.g.
> choose between KDL::Twist, std::vector, geometry_msgs:Twist.
>
> - So my first question is, what is the best way of doing this? Would you
> even recommend it?
>
> - The second question is about how I implemented it:
>
> in hpp:
>
> *typedef RTT::InputPort< KDL::Twist > PortType_IN_KDL;*
> *typedef RTT::InputPort< geometry_msgs::Twist > PortType_IN_GEO;*
> *typedef RTT::InputPort< std::vector<double> > PortType_IN_VEC;*
>
> *boost::shared_ptr< PortType_IN_VEC > vel_vec_inport_;*
> *boost::shared_ptr< PortType_IN_GEO > vel_geo_inport_;*
> *boost::shared_ptr< PortType_IN_KDL > vel_kdl_inport_;*
>
> and then in configureHook in cpp did this for each:
>
> vel_vec_inport_ = boost::make_shared< CartPortType_IN_VEC>();
> this->addPort("vel_vec_inport",*vel_vec_inport_).doc("velocity inport in
> std::vector format");
>
>
> The problem is that once I start the component, stopping it will cause
> problem. Either for orocos or for the component itself...
>
> Inside deployer if I call component.stop and then component.cleanup it
> doesn't complain. But if I now call 'configure', it goes to the famous
> error "pure virtual method called, terminate called without an active
> exception"... I also tried to reset the shared pointer with
>
> vel_vec_inport_.reset()
>
> But that doesn't seem to help. I tried calling this->removePort(vel_vec_inport_)
> in cleanup, but that doesn't even compile...
>
>
> If once the component has started, I exit deployer I get the error:
>
> *terminate called after throwing an instance of
> 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector > >'*
> * what(): boost: mutex lock failed in pthread_mutex_lock: Invalid
> argument*
> */opt/ros/indigo/lib/rtt_ros/deployer: line 5: 24934
> Aborted (core dumped) deployer "$@"*
>
> I would appreciate if you have any idea why things go wrong here...
>
> Thanks
>
> Cheers
>
> Keivan
>
>
>