Skip to content
Snippets Groups Projects
Commit 900d78b6 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Changes in the scripts to implement the chnages in the iri_base_driver class...

Changes in the scripts to implement the chnages in the iri_base_driver class due to the deprecation of the ROS driver_base class.
parent 073e9a21
No related branches found
No related tags found
1 merge request!1Kinetic migration
......@@ -33,7 +33,7 @@
PACKAGE='template'
from driver_base.msg import SensorLevels
from iri_base_driver.msg import SensorLevels
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
......
......@@ -35,13 +35,13 @@ void TemplateDriver::config_update(Config& new_cfg, uint32_t level)
// update driver with new_cfg data
switch(this->getState())
{
case TemplateDriver::CLOSED:
case iri_base_driver::CLOSED:
break;
case TemplateDriver::OPENED:
case iri_base_driver::OPENED:
break;
case TemplateDriver::RUNNING:
case iri_base_driver::RUNNING:
break;
}
......
......@@ -4,7 +4,7 @@ TemplateNode::TemplateNode(ros::NodeHandle &nh) :
iri_base_driver::IriBaseNodeDriver<TemplateDriver>(nh)
{
//init class attributes if necessary
//this->loop_rate_ = 2;//in [Hz]
//this->setRate(10);//in [Hz]
// [init publishers]
......@@ -50,23 +50,15 @@ void TemplateNode::postNodeOpenHook(void)
{
}
void TemplateNode::addNodeDiagnostics(void)
{
}
void TemplateNode::addNodeOpenedTests(void)
void TemplateNode::preNodeCloseHook(void)
{
}
void TemplateNode::addNodeStoppedTests(void)
{
}
void TemplateNode::addNodeRunningTests(void)
void TemplateNode::addNodeDiagnostics(void)
{
}
void TemplateNode::reconfigureNodeHook(int level)
void TemplateNode::node_config_update(Config& new_cfg, uint32_t level)
{
}
......@@ -78,5 +70,5 @@ TemplateNode::~TemplateNode(void)
/* main function */
int main(int argc,char *argv[])
{
return driver_base::main<TemplateNode>(argc, argv, "template_node");
return iri_base_driver::main<TemplateNode>(argc, argv, "template_node");
}
......@@ -75,6 +75,8 @@ class TemplateNode : public iri_base_driver::IriBaseNodeDriver<TemplateDriver>
*/
void postNodeOpenHook(void);
void preNodeCloseHook(void);
public:
/**
* \brief constructor
......@@ -134,39 +136,6 @@ class TemplateNode : public iri_base_driver::IriBaseNodeDriver<TemplateDriver>
// [driver test functions]
/**
* \brief open status driver tests
*
* In this function tests checking driver's functionallity when driver_base
* status=open can be added. Common use tests for all nodes are already called
* from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
* please refer to the Self Test example in:
* http://www.ros.org/wiki/self_test/
*/
void addNodeOpenedTests(void);
/**
* \brief stop status driver tests
*
* In this function tests checking driver's functionallity when driver_base
* status=stop can be added. Common use tests for all nodes are already called
* from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
* please refer to the Self Test example in:
* http://www.ros.org/wiki/self_test/
*/
void addNodeStoppedTests(void);
/**
* \brief run status driver tests
*
* In this function tests checking driver's functionallity when driver_base
* status=run can be added. Common use tests for all nodes are already called
* from IriBaseNodeDriver tests methods. For more details on how ROS tests work,
* please refer to the Self Test example in:
* http://www.ros.org/wiki/self_test/
*/
void addNodeRunningTests(void);
/**
* \brief specific node dynamic reconfigure
*
......@@ -174,7 +143,7 @@ class TemplateNode : public iri_base_driver::IriBaseNodeDriver<TemplateDriver>
*
* \param level integer
*/
void reconfigureNodeHook(int level);
void node_config_update(Config& new_cfg, uint32_t level);
};
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment