Connecting ports

Hello,

I'm trying to communicate with an EtherCAT stack through ROS.

In the deployer I've got successfully the HelloRobot and the SoemMaster peers running simultaneously.

I read chapter four of the orocos components manual for connecting TaskContexts. http://people.mech.kuleuven.be/~orocos/pub/documentation/rtt/v1.8.x/doc-xml/orocos-components-manual.html#connect-tasks

However I cannot figure out where to put the connectPeers commands.

For a simple start I would like to connect a port from HelloRobot to a data flow port from a slave. For example Slave_1003_values which is an analog output. (EL4038).

Connecting ports

On Friday 17 September 2010 14:35:47 t [dot] t [dot] g [dot] clephas [..] ... wrote:
> Hello,
>
> I'm trying to communicate with an EtherCAT stack through ROS.
>
> In the deployer I've got successfully the HelloRobot and the SoemMaster
> peers running simultaneously.
>
> I read chapter four of the orocos components manual for connecting
> TaskContexts.
> http://people.mech.kuleuven.be/~orocos/pub/documentation/rtt/v1.8.x/doc-xm
> l/orocos-components-manual.html#connect-tasks

This is a completely wrong link. Be sure to read the v2.0 documentation here:

http://www.orocos.org/stable/documentation/rtt/v2.0.x/doc-xml/orocos-
components-manual.html#connect-tasks

>
> However I cannot figure out where to put the connectPeers commands.
>
>
> For a simple start I would like to connect a port from HelloRobot to a data
> flow port from a slave. For example Slave_1003_values which is an analog
> output. (EL4038).

There is a big difference between 'peers' and 'ports'. The former is for task-
browsing, and calling each other's operations, the latter is for data
streaming.

If you want to connect using the XML file format, consult the deployment
component manual here:
http://www.orocos.org/stable/documentation/ocl/v2.0.x/doc-xml/orocos-
deployment.html (See: 'Connecting Data Ports')

Using the taskbrowser, you can connect two ports using the 'connectPorts'
operation. For example :
connectPorts("HelloRobot","DrivePort","SoemMaster","Slave_1003_values")

Peter

Connecting ports

Thanks, this helped a lot.

I've got two peers running with connected ports. One receives messages from a ros topic and sends it through to the other one.

Of course the types of ports must agree. However SoemMaster uses a type: <AnalogMsg>
I can make a port of that type, but I can't figure out what to send to it.

The file I'm trying to run is this one:

#include <rtt/TaskContext.hpp>
#include <rtt/Port.hpp>
#include <ocl/Component.hpp>
#include <soem_beckhoff_drivers/AnalogMsg.h>
 
using namespace RTT;
 
class WritePort : public RTT::TaskContext{
private:  
 
  soem_beckhoff_drivers::AnalogMsg msg;
  std::vector<double> values;
  OutputPort<soem_beckhoff_drivers::AnalogMsg> values_port;
 
public:
  WritePort(const std::string& name):
    TaskContext(name),
    values_port("analog_out")
  {
    ports()->addPort(values_port);
  }
  ~WritePort(){}
 
private:
  void updateHook(){
    values_port.write(????);
  }
};
ORO_CREATE_COMPONENT(WritePort)

The question is, what can I put in place of the question marks. I can't figure out how the msg variable is build up.

The AnalogMsg.msg says float32[] values but that isn't of much help.
And the port description says "AnalogMsg containing the desired values of _all_ channels"

Thanks in advance,

Tim

Connecting ports

Thanks, this helped a lot.

I've got two peers running with connected ports. One receives messages from a ros topic and sends it through to the other one.

Of course the types of ports must agree. However SoemMaster uses a type: <AnalogMsg> I can make a port of that type, but I can't figure out what to send to it.

The file I'm trying to run is this one:

#include <rtt/TaskContext.hpp>
#include <rtt/Port.hpp>
#include <ocl/Component.hpp>
#include <soem_beckhoff_drivers/AnalogMsg.h>
 
using namespace RTT;
 
class WritePort : public RTT::TaskContext{
private:  
 
  soem_beckhoff_drivers::AnalogMsg msg;
  std::vector<double> values;
  OutputPort<soem_beckhoff_drivers::AnalogMsg> values_port;
 
public:
  WritePort(const std::string& name):
    TaskContext(name),
    values_port("analog_out")
  {
    ports()->addPort(values_port);
  }
  ~WritePort(){}
 
private:
  void updateHook(){
    values_port.write(????);
  }
};
ORO_CREATE_COMPONENT(WritePort)

The question is, what can I put in place of the question marks. I can't figure out how the msg variable is build up.

The AnalogMsg.msg says float32[] values but that isn't of much help. And the port description says "AnalogMsg containing the desired values of _all_ channels"

Thanks in advance,

Tim

Ruben Smits's picture

Connecting ports

On Wednesday 22 September 2010 13:51:49 t [dot] t [dot] g [dot] clephas [..] ... wrote:
> Thanks, this helped a lot.
>
> I've got two peers running with connected ports. One receives messages from
> a ros topic and sends it through to the other one.
>
> Of course the types of ports must agree. However SoemMaster uses a type:
> <AnalogMsg> I can make a port of that type, but I can't figure out what to
> send to it.
>
> The file I'm trying to run is this one:
>
>

> #include <rtt/TaskContext.hpp>
> #include <rtt/Port.hpp>
> #include <ocl/Component.hpp>
> #include <soem_beckhoff_drivers/AnalogMsg.h>
> 
> using namespace RTT;
> 
> class WritePort : public RTT::TaskContext{
> private:
> 
>   soem_beckhoff_drivers::AnalogMsg msg;
>   std::vector<double> values;
>   OutputPort<soem_beckhoff_drivers::AnalogMsg> values_port;
> 
> public:
>   WritePort(const std::string& name):
>     TaskContext(name),
>     values_port("analog_out")
>   {
>     ports()->addPort(values_port);
>   }
>   ~WritePort(){}
> 
> private:
>   void updateHook(){
>     values_port.write(????);
>   }
> };
> ORO_CREATE_COMPONENT(WritePort)
> 

>
>
> The question is, what can I put in place of the question marks. I can't
> figure out how the msg variable is build up.
>

You have to put a AnalogMsg in place of the question marks.
AnalogMsg msg;
msg.values = ...
values_port.write(msg);

> The AnalogMsg.msg says float32[] values but that isn't of much help.
> And the port description says "AnalogMsg containing the desired values of
> _all_ channels"

The size of the float32 array depends on the beckhoff module you are using, some
have 2 channels, others up to 8. If you send a message of the wrong size the
driver will complain or not send the requested values to the slave.

Ruben
> Thanks in advance,
>
> Tim

Awesome,I went wrong on the

Awesome,

I went wrong on the msg.values=...

Everything is up and running now. The EtherCAT stack can be controlled by ROS with a controller in realtime.

I've got two peers communicating by the command:

connectTwoPorts("Controller","volt3_out","SoemMaster","Slave_1003_values")

This means I have to type this command constantly.
I want to connect the ports through the xml file.

<struct name="Controller" type="Controller">
  <struct name="Activity" type="PeriodicActivity">
    <simple name="Period" type="double"><value>1</value></simple>
    <simple name="Priority" type="short"><value>0</value></simple>
    <simple name="Scheduler" type="string"><value>ORO_SCHED_RT</value></simple>
  </struct>
  <struct name="Peers" type="PropertyBag">
    <simple type="string"><value>SoemMaster</value></simple>
  </struct>
  <struct name="Ports" type="PropertyBag">
    <simple name="volt3_out" type="string"><value>Voltage3</value></simple>
  </struct>
  <simple name="AutoConf" type="boolean"><value>1</value></simple>
  <simple name="AutoStart" type="boolean"><value>1</value></simple>
  <simple name="AutoConnect" type="boolean"><value>1</value></simple>
</struct>
 
<struct name="SoemMaster" type="soem_master::SoemMasterComponent">
  <struct name="Activity" type="PeriodicActivity">
    <simple name="Period" type="double"><value>0.001</value></simple>
    <simple name="Priority" type="short"><value>0</value></simple>
    <simple name="Scheduler" type="string"><value>ORO_SCHED_RT</value></simple>
  </struct>
  <struct name="Peers" type="PropertyBag">
    <simple type="string"><value>Controller</value></simple>
  </struct>
  <struct name="Ports" type="PropertyBag">
    <simple name="Slave_1003_values" type="string"><value>Voltage3</value></simple>
  </struct>
  <simple name="AutoConf" type="boolean"><value>1</value></simple>
  <simple name="AutoStart" type="boolean"><value>1</value></simple>
  <simple name="AutoConnect" type="boolean"><value>1</value></simple>
</struct>

This should work, but SoemMaster doesn't have any ports until it is configured.

So how to configure first, then connect the port?

Thanks,

Awesome,I went wrong on the

Awesome,

I went wrong on the msg.values=...

Everything is up and running now. The EtherCAT stack can be controlled by ROS with a controller in realtime.

I've got two peers communicating by the command:

connectTwoPorts("Controller","volt3_out","SoemMaster","Slave_1003_values")

This means I have to type this command constantly. I want to connect the ports through the xml file.

<struct name="Controller" type="Controller">
  <struct name="Activity" type="PeriodicActivity">
    <simple name="Period" type="double"><value>1</value></simple>
    <simple name="Priority" type="short"><value>0</value></simple>
    <simple name="Scheduler" type="string"><value>ORO_SCHED_RT</value></simple>
  </struct>
  <struct name="Peers" type="PropertyBag">
    <simple type="string"><value>SoemMaster</value></simple>
  </struct>
  <struct name="Ports" type="PropertyBag">
    <simple name="volt3_out" type="string"><value>Voltage3</value></simple>
  </struct>
  <simple name="AutoConf" type="boolean"><value>1</value></simple>
  <simple name="AutoStart" type="boolean"><value>1</value></simple>
  <simple name="AutoConnect" type="boolean"><value>1</value></simple>
</struct>
 
<struct name="SoemMaster" type="soem_master::SoemMasterComponent">
  <struct name="Activity" type="PeriodicActivity">
    <simple name="Period" type="double"><value>0.001</value></simple>
    <simple name="Priority" type="short"><value>0</value></simple>
    <simple name="Scheduler" type="string"><value>ORO_SCHED_RT</value></simple>
  </struct>
  <struct name="Peers" type="PropertyBag">
    <simple type="string"><value>Controller</value></simple>
  </struct>
  <struct name="Ports" type="PropertyBag">
    <simple name="Slave_1003_values" type="string"><value>Voltage3</value></simple>
  </struct>
  <simple name="AutoConf" type="boolean"><value>1</value></simple>
  <simple name="AutoStart" type="boolean"><value>1</value></simple>
  <simple name="AutoConnect" type="boolean"><value>1</value></simple>
</struct>

This should work, but SoemMaster doesn't have any ports until it is configured.

So how to configure first, then connect the port?

Thanks,

Awesome,I went wrong on the

On Thu, Sep 23, 2010 at 4:45 PM, <t [dot] t [dot] g [dot] clephas [..] ...> wrote:
> Awesome,
>
> I went wrong on the msg.values=...
>
> Everything is up and running now. The EtherCAT stack can be controlled by ROS with a controller in realtime.
>
> I've got two peers communicating by the command:
>
> connectTwoPorts("Controller","volt3_out","SoemMaster","Slave_1003_values")
>
> This means I have to type this command constantly.
> I want to connect the ports through the xml file.

...
> This should work, but SoemMaster doesn't have any ports until it is configured.
>
> So how to configure first, then connect the port?

The current system is far from perfect when you deviate from the
common path. What you could do is make 2 xml files,
one wich you use to kickstart the soem master (ie load it and
configure it). Then kickstart the second one which contains the port
connections. Specifying port connections is a hassle right now in XML.
It's verbose and spread around the whole file.

You can also put everything in a .ops script and load that one in the
deployer. As such you don't need to use the XML
format and you have a more readable file. You could keep the XML file
for just describing which components to load
and the program file to configure/connect them. For example:

   <struct name="SoemMaster" type="soem_master::SoemMasterComponent"></struct>
   <struct name="Controller" type="Controller"></struct>
   <struct name="Deployer"  type="PropertyBag">
      <simple name="ProgramScript" type="string"><value>startup.ops</value>
   </struct>

And the program file startup.ops does:
program startup {
SoemMaster.configure()
connectTwoPorts("Controller","volt3_out","SoemMaster","Slave_1003_values")
/// etc...
}

This might be much easier to do than doing the whole thing in XML.
Take note that
you need to start the startup program manually in the TaskBrowser:
startup.start()

Peter

Not working

Somehow this doesn't work for me. The files I'm using:

<?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE properties SYSTEM "cpf.dtd">
<properties>
<simple name="Import" type="string"><value>$(find communicate_with_EtherCAT)/lib/orocos</value></simple>
 
<struct name="Controller" type="Controller">
  <struct name="Activity" type="PeriodicActivity">
    <simple name="Period" type="double"><value>0.001</value></simple>
    <simple name="Priority" type="short"><value>1</value></simple>
    <simple name="Scheduler" type="string"><value>ORO_SCHED_RT</value></simple>
  </struct>
  <simple name="AutoConf" type="boolean"><value>1</value></simple>
</struct>
 
<struct name="Deployer"  type="PropertyBag">
   <simple name="ProgramScript" type="string"><value>startup.ops</value></simple>
</struct>
 
</properties>

And:
startup.ops

program startup {
do Controller.start()
}

Gives:

In Task Deployer[S]
 (type 'ls' for context info) :ls
 
 Listing TaskContext Deployer :
 
 Configuration Properties: 
     string RTT_COMPONENT_PATH = /home/s050745/ros/kul-ros-pkg/stacks/orocos_toolchain_ros/trunk/rtt/install/lib/orocos
       bool AutoUnload     = true
     string Target         = gnulinux
 
 Provided Interface:
  Attributes   : 
       bool Valid          = true                
        int ORO_SCHED_RT   = 1                   
        int ORO_SCHED_OTHER = 0                   
        int LowestPriority = 1                   
        int HighestPriority = 99                  
 
  Operations      : activate addPeer cleanup ... etc ... unloadComponents update 
 
 Data Flow Ports: (none)
 
 Services: 
       scripting ( Orocos Scripting service. Use this service in order to load or query programs or state machines. ) 
         startup ( Orocos Program Script ) 
 
 Requires Operations :  (none)
 Requests Services   :  (none)
 Programs     : startup[S] 
 
 Peers        : Controller[S] 
 
 In Task Deployer[S]
 (type 'ls' for context info) :startup.start()
      Got :startup.start()
 = true                
 
 In Task Deployer[S]
 (type 'ls' for context info) :ls
 
 Listing TaskContext Deployer :
 
 Configuration Properties: 
     string RTT_COMPONENT_PATH = /home/s050745/ros/kul-ros-pkg/stacks/orocos_toolchain_ros/trunk/rtt/install/lib/orocos
       bool AutoUnload     = true
     string Target         = gnulinux
 
 Provided Interface:
  Attributes   : 
       bool Valid          = true                
        int ORO_SCHED_RT   = 1                   
        int ORO_SCHED_OTHER = 0                   
        int LowestPriority = 1                   
        int HighestPriority = 99                  
 
  Operations      : activate addPeer cleanup ... unloadComponents update 
 
 Data Flow Ports: (none)
 
 Services: 
       scripting ( Orocos Scripting service. Use this service in order to load or query programs or state machines. ) 
         startup ( Orocos Program Script ) 
 
 Requires Operations :  (none)
 Requests Services   :  (none)
 Programs     : startup[R] 
 
 Peers        : Controller[S] 
 
 In Task Deployer[S]
 (type 'ls' for context info) :

So the Controller component still doesn't start by running the startup.ops script.

Any suggestions?

Thanks,

Tim

Not working

Somehow this doesn't work for me. The files I'm using:

<?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE properties SYSTEM "cpf.dtd">
<properties>
<simple name="Import" type="string"><value>$(find communicate_with_EtherCAT)/lib/orocos</value></simple>
 
<struct name="Controller" type="Controller">
  <struct name="Activity" type="PeriodicActivity">
    <simple name="Period" type="double"><value>0.001</value></simple>
    <simple name="Priority" type="short"><value>1</value></simple>
    <simple name="Scheduler" type="string"><value>ORO_SCHED_RT</value></simple>
  </struct>
  <simple name="AutoConf" type="boolean"><value>1</value></simple>
</struct>
 
<struct name="Deployer"  type="PropertyBag">
   <simple name="ProgramScript" type="string"><value>startup.ops</value></simple>
</struct>
 
</properties>

And: startup.ops

program startup {
do Controller.start()
}

Gives:

In Task Deployer[S]
 (type 'ls' for context info) :ls
 
 Listing TaskContext Deployer :
 
 Configuration Properties: 
     string RTT_COMPONENT_PATH = /home/s050745/ros/kul-ros-pkg/stacks/orocos_toolchain_ros/trunk/rtt/install/lib/orocos
       bool AutoUnload     = true
     string Target         = gnulinux
 
 Provided Interface:
  Attributes   : 
       bool Valid          = true                
        int ORO_SCHED_RT   = 1                   
        int ORO_SCHED_OTHER = 0                   
        int LowestPriority = 1                   
        int HighestPriority = 99                  
 
  Operations      : activate addPeer cleanup ... etc ... unloadComponents update 
 
 Data Flow Ports: (none)
 
 Services: 
       scripting ( Orocos Scripting service. Use this service in order to load or query programs or state machines. ) 
         startup ( Orocos Program Script ) 
 
 Requires Operations :  (none)
 Requests Services   :  (none)
 Programs     : startup[S] 
 
 Peers        : Controller[S] 
 
 In Task Deployer[S]
 (type 'ls' for context info) :startup.start()
      Got :startup.start()
 = true                
 
 In Task Deployer[S]
 (type 'ls' for context info) :ls
 
 Listing TaskContext Deployer :
 
 Configuration Properties: 
     string RTT_COMPONENT_PATH = /home/s050745/ros/kul-ros-pkg/stacks/orocos_toolchain_ros/trunk/rtt/install/lib/orocos
       bool AutoUnload     = true
     string Target         = gnulinux
 
 Provided Interface:
  Attributes   : 
       bool Valid          = true                
        int ORO_SCHED_RT   = 1                   
        int ORO_SCHED_OTHER = 0                   
        int LowestPriority = 1                   
        int HighestPriority = 99                  
 
  Operations      : activate addPeer cleanup ... unloadComponents update 
 
 Data Flow Ports: (none)
 
 Services: 
       scripting ( Orocos Scripting service. Use this service in order to load or query programs or state machines. ) 
         startup ( Orocos Program Script ) 
 
 Requires Operations :  (none)
 Requests Services   :  (none)
 Programs     : startup[R] 
 
 Peers        : Controller[S] 
 
 In Task Deployer[S]
 (type 'ls' for context info) :

So the Controller component still doesn't start by running the startup.ops script.

Any suggestions?

Thanks,

Tim

Not working

On Tuesday 28 September 2010 13:35:17 t [dot] t [dot] g [dot] clephas [..] ... wrote:
> Somehow this doesn't work for me. The files I'm using:
>
>

> <?xml version="1.0" encoding="UTF-8"?>
> <!DOCTYPE properties SYSTEM "cpf.dtd">
> <properties>
> <simple name="Import" type="string"><value>$(find
> communicate_with_EtherCAT)/lib/orocos</value></simple>
> 
> <struct name="Controller" type="Controller">
>   <struct name="Activity" type="PeriodicActivity">
>     <simple name="Period" type="double"><value>0.001</value></simple>
>     <simple name="Priority" type="short"><value>1</value></simple>
>     <simple name="Scheduler"
> type="string"><value>ORO_SCHED_RT</value></simple> </struct>
>   <simple name="AutoConf" type="boolean"><value>1</value></simple>
> </struct>
> 
> <struct name="Deployer"  type="PropertyBag">
>    <simple name="ProgramScript"
> type="string"><value>startup.ops</value></simple> </struct>
> 
> </properties>
> 

>
> And:
> startup.ops
>
> program startup {
> do Controller.start()
> }
> 

>
> Gives:
>
>
> In Task Deployer[S]
>  (type 'ls' for context info) :ls
> 
>  Listing TaskContext Deployer :
> 
>  Configuration Properties:
>      string RTT_COMPONENT_PATH =
> /home/s050745/ros/kul-ros-pkg/stacks/orocos_toolchain_ros/trunk/rtt/instal
> l/lib/orocos bool AutoUnload     = true
>      string Target         = gnulinux
> 
>  Provided Interface:
>   Attributes   :
>        bool Valid          = true
>         int ORO_SCHED_RT   = 1
>         int ORO_SCHED_OTHER = 0
>         int LowestPriority = 1
>         int HighestPriority = 99
> 
>   Operations      : activate addPeer cleanup ... etc ... unloadComponents
> update
> 
>  Data Flow Ports: (none)
> 
>  Services:
>        scripting ( Orocos Scripting service. Use this service in order to
> load or query programs or state machines. ) startup ( Orocos Program
> Script )
> 
>  Requires Operations :  (none)
>  Requests Services   :  (none)
>  Programs     : startup[S]
> 
>  Peers        : Controller[S]
> 
>  In Task Deployer[S]
>  (type 'ls' for context info) :startup.start()
>       Got :startup.start()
>  = true
> 
>  In Task Deployer[S]
>  (type 'ls' for context info) :ls
> 
>  Listing TaskContext Deployer :
> 
>  Configuration Properties:
>      string RTT_COMPONENT_PATH =
> /home/s050745/ros/kul-ros-pkg/stacks/orocos_toolchain_ros/trunk/rtt/instal
> l/lib/orocos bool AutoUnload     = true
>      string Target         = gnulinux
> 
>  Provided Interface:
>   Attributes   :
>        bool Valid          = true
>         int ORO_SCHED_RT   = 1
>         int ORO_SCHED_OTHER = 0
>         int LowestPriority = 1
>         int HighestPriority = 99
> 
>   Operations      : activate addPeer cleanup ... unloadComponents update
> 
>  Data Flow Ports: (none)
> 
>  Services:
>        scripting ( Orocos Scripting service. Use this service in order to
> load or query programs or state machines. ) startup ( Orocos Program
> Script )
> 
>  Requires Operations :  (none)
>  Requests Services   :  (none)
>  Programs     : startup[R]
> 
>  Peers        : Controller[S]
> 
>  In Task Deployer[S]
>  (type 'ls' for context info) :
> 

>
> So the Controller component still doesn't start by running the startup.ops
> script.
>
> Any suggestions?

In order to see what your program is doing, you can type 'list startup' in the
TaskBrowser. Since 'startup' is still in the 'Running' state ([R], it looks
like the start() operation blocks. I'll try to reproduce it here.

Peter

Not working

On Thursday 30 September 2010 13:49:24 Peter Soetens wrote:
> On Tuesday 28 September 2010 13:35:17 t [dot] t [dot] g [dot] clephas [..] ... wrote:
> > Somehow this doesn't work for me. The files I'm using:
> >
...
> >
> > So the Controller component still doesn't start by running the
> > startup.ops script.

I can confirm this... looking at it.

Peter

Not working

On Thursday 30 September 2010 14:01:54 Peter Soetens wrote:
> On Thursday 30 September 2010 13:49:24 Peter Soetens wrote:
> > On Tuesday 28 September 2010 13:35:17 t [dot] t [dot] g [dot] clephas [..] ... wrote:
> > > Somehow this doesn't work for me. The files I'm using:
> ...
>
> > > So the Controller component still doesn't start by running the
> > > startup.ops script.
>
> I can confirm this... looking at it.

Oh darn ! It's your deployer not having a period. We should probably print a
warning when loading scripts in such components...

Try this XML file:

code>
<?xml version="1.0" encoding="UTF-8"?>
&lt;!DOCTYPE properties SYSTEM "cpf.dtd"&gt;
<properties>
<simple name="Import" type="string"><value>$(find
communicate_with_EtherCAT)/lib/orocos<value><simple>

<struct name="Controller" type="Controller">
<struct name="Activity" type="PeriodicActivity">
<simple name="Period" type="double"><value>0.001<value><simple>
<simple name="Priority" type="short"><value>1<value><simple>
<simple name="Scheduler"
type="string"><value>ORO_SCHED_RT<value><simple>
<struct>
<simple name="AutoConf" type="boolean"><value>1<value><simple>
<struct>

<struct name="Deployer" type="PropertyBag">
<simple name="ProgramScript"
type="string"><value>startup.ops<value><simple>
<struct name="Activity" type="Activity">
<simple name="Period" type="double"><value>0.1<value><simple>
<simple name="Priority" type="short"><value>0<value><simple>
<simple name="Scheduler"
type="string"><value>ORO_SCHED_OTHER<value><simple>
<struct>
<struct>

<properties>

Alternatively, you can just call 'setPeriod(0.1)' at the deployer's prompt in
your current configuration...

Peter

PS: 'PeriodicActivity' should only be used in special cases. Please use the
flexible 'Activity' in most cases.

Awesome,I went wrong on

Apparently I'm deviating from the common path.

This makes me wonder what the common path is. I'm trying to control a motor through an EtherCAT stack. And a ROS node generates the reference path.

So the way I have done it now: One component reads the reference value from a ros topic. A controller is implemented in C++ code to run with UpdateHook().

These resulting value (voltage in this case) is send through a port to the SoemMaster which communicates it to the EtherCAT stack.

This seemed logical to me, but if there's a more common path to do this, I'm curious to learn :)

Awesome,I went wrong on the

Apparently I'm deviating from the common path.

This makes me wonder what the common path is. I'm trying to control a motor through an EtherCAT stack. And a ROS node generates the reference path.

So the way I have done it now: One component reads the reference value from a ros topic. A controller is implemented in C++ code to run with UpdateHook().

These resulting value (voltage in this case) is send through a port to the SoemMaster which communicates it to the EtherCAT stack.

This seemed logical to me, but if there's a more common path to do this, I'm curious to learn :)

Awesome,I went wrong on

On Mon, 27 Sep 2010, t [dot] t [dot] g [dot] clephas [..] ... wrote:

> Apparently I'm deviating from the common path.
>
> This makes me wonder what the common path is. I'm trying to control a motor through an EtherCAT stack. And a ROS node generates the reference path.
>
> So the way I have done it now: One component reads the reference value from a ros topic. A controller is implemented in C++ code to run with UpdateHook().
>
> These resulting value (voltage in this case) is send through a port to the SoemMaster which communicates it to the EtherCAT stack.
>
> This seemed logical to me, but if there's a more common path to do this, I'm curious to learn :)

This approach sounds normal and decent :-)

You _could_ opt for another architecture:
- the Orocos component is also doing the trajectory generation (because
this is simpler to keep in sync with the controller)
- in a first state of the Orocos component, you initialize the trajectory
generation, if needed
- after that, you call the update function for the trajectory generator
(maybe not every sample period of the controller, but only once every ten
times or so).
- you do your control as in your suggestion.

Herman

Connecting ports

Hello,

I'm trying to communicate with an EtherCAT stack through ROS.

In the deployer I've got successfully the HelloRobot and the SoemMaster peers running simultaneously.

I read chapter four of the orocos components manual for connecting TaskContexts.
http://people.mech.kuleuven.be/~orocos/pub/documentation/rtt/v1.8.x/doc-...

However I cannot figure out where to put the connectPeers commands.

For a simple start I would like to connect a port from HelloRobot to a data flow port from a slave. For example Slave_1003_values which is an analog output. (EL4038).