Skip to content
Snippets Groups Projects
Commit f3d17270 authored by Joan Vallvé Navarro's avatar Joan Vallvé Navarro
Browse files

added problem/node_rate in YAMLS params

parent f39a0c81
No related branches found
No related tags found
2 merge requests!11new release,!10new release
...@@ -95,8 +95,10 @@ class WolfRosNode ...@@ -95,8 +95,10 @@ class WolfRosNode
int print_depth_; int print_depth_;
bool print_constr_by_, print_metric_, print_state_blocks_; bool print_constr_by_, print_metric_, print_state_blocks_;
public: public:
double node_rate_;
WolfRosNode(); WolfRosNode();
virtual ~WolfRosNode(){}; virtual ~WolfRosNode(){};
......
...@@ -56,7 +56,10 @@ WolfRosNode::WolfRosNode() ...@@ -56,7 +56,10 @@ WolfRosNode::WolfRosNode()
ROS_INFO("Creating solver..."); ROS_INFO("Creating solver...");
solver_ = FactorySolver::create("SolverCeres", problem_ptr_, server); solver_ = FactorySolver::create("SolverCeres", problem_ptr_, server);
// ROS SUBSCRIBERS // ROS
node_rate_ = server.getParam<double>("problem/node_rate");
// SUBSCRIBERS
ROS_INFO("Creating subscribers..."); ROS_INFO("Creating subscribers...");
for (auto it : server.getParam<std::vector<std::map<std::string, std::string>>>("ROS subscriber")) for (auto it : server.getParam<std::vector<std::map<std::string, std::string>>>("ROS subscriber"))
{ {
...@@ -67,7 +70,7 @@ WolfRosNode::WolfRosNode() ...@@ -67,7 +70,7 @@ WolfRosNode::WolfRosNode()
subscribers_.push_back(FactorySubscriber::create(subscriber, subscriber+" - "+topic, server, problem_ptr_->getSensor(sensor), nh_)); subscribers_.push_back(FactorySubscriber::create(subscriber, subscriber+" - "+topic, server, problem_ptr_->getSensor(sensor), nh_));
} }
// ROS PUBLISHERS // PUBLISHERS
ROS_INFO("Creating publishers..."); ROS_INFO("Creating publishers...");
for (auto it : server.getParam<std::vector<std::map<std::string, std::string>>>("ROS publisher")) for (auto it : server.getParam<std::vector<std::map<std::string, std::string>>>("ROS publisher"))
{ {
...@@ -208,7 +211,7 @@ int main(int argc, char **argv) ...@@ -208,7 +211,7 @@ int main(int argc, char **argv)
// Wolf node // Wolf node
WolfRosNode wolf_node; WolfRosNode wolf_node;
ros::Rate loopRate(100); ros::Rate loopRate(wolf_node.node_rate_);
// periodic stuff // periodic stuff
ros::Time last_check = ros::Time::now(); ros::Time last_check = ros::Time::now();
......
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