From 10135b7ade3fed978e0a2dcab4fc07ca9fe597a3 Mon Sep 17 00:00:00 2001 From: jschleicher Date: Tue, 11 Jun 2019 14:42:54 +0200 Subject: [PATCH] reset node on initialization Resetting the communication only loads default values for the pdo mapping in the motor firmware according to CiA 301. Also reset the application registers to get a roslaunch behaviour that is similar to a power-on-reset of the motor to recover from errors and values from the previous run. --- canopen_master/src/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/canopen_master/src/node.cpp b/canopen_master/src/node.cpp index 21edbd027..be24ed75b 100644 --- a/canopen_master/src/node.cpp +++ b/canopen_master/src/node.cpp @@ -178,7 +178,7 @@ void Node::handleInit(LayerStatus &status){ sdo_.init(); try{ - if(!reset_com()) BOOST_THROW_EXCEPTION( TimeoutException("reset_timeout") ); + if(!reset()) BOOST_THROW_EXCEPTION( TimeoutException("reset_timeout") ); } catch(const TimeoutException&){ status.error(boost::str(boost::format("could not reset node '%1%'") % (int)node_id_));