Re: [ros-users] Best way to set the parameters for the contr…

Top Page
Attachments:
Message as email
+ (text/plain)
+ msg_to_pcd.cpp (text/x-c++src)
Delete this message
Reply to this message
Author: Dejan Pangercic
Date:  
To: ros-users
Subject: Re: [ros-users] Best way to set the parameters for the controllers (param or message?)
Ugo,

as our guru Lorenz just pointed out, please note that the earlier
attached code was actually taking 100% of CPU.
I am attaching an improved version with added sleep in the spin function.
D.

On Mon, Apr 19, 2010 at 8:18 PM, Dejan Pangercic
<> wrote:
> Hi Ugo,
>
> I am by no means authority but this is the way I update parameters in my nodes:
> Define node's member function, e.g.:
> /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
>  double param_;
>  void
>      updateParametersFromServer ()
>    {
>      nh_.getParam ("my_param", param_);
>    }
> and then constantly call it in that node's spin function:
>
>      updateParametersFromServer ();
>
> See also an attached example file.
>
> Furthermore, I just recently stumbled upon
> http://www.ros.org/wiki/dynamic_reconfigure which "facilitates dynamic
> node reconfiguration". However I do not really understand in how far
> is it different to conventional updating of parameters as discussed
> before. But maybe Blaise can tell here more.
>
> D.
> On Mon, Apr 19, 2010 at 6:56 PM, Ugo Cupcic <> wrote:
>> Hi,
>>
>> I'm currently setting the parameters for the controllers (PID and so on)
>> via a message (I have a subscriber which updates the values when it
>> receives the corresponding message).
>>
>> It works well, but I wanted to know what was the recommended way of
>> doing that in ROS. Is it better to do it using parameters? (But then how
>> can I  change the corresponding values when the parameters are updated?)
>>
>> Cheers,
>>
>> Ugo
>>
>> --
>> Ugo Cupcic         |  Shadow Robot Company |
>> Software Engineer      251 Liverpool Road
>> need a Hand?           London  N1 1LX       | +44 20 7700 2487
>> http://www.shadowrobot.com/hand/              @shadowrobot
>>
>>
>> _______________________________________________
>> ros-users mailing list
>>
>> https://code.ros.org/mailman/listinfo/ros-users
>>
>
>
>
> --
> MSc. Dejan Pangercic
> PhD Student/Researcher
> Computer Science IX
> Technische Universität München
> Telephone: +49 (89) 289-17780
> E-Mail:
> WWW: http://ias.cs.tum.edu/people/pangercic
>




--
MSc. Dejan Pangercic
PhD Student/Researcher
Computer Science IX
Technische Universität München
Telephone: +49 (89) 289-17780
E-Mail:
WWW: http://ias.cs.tum.edu/people/pangercic
// #include <unistd.h>

#include <ctime>
#include <ros/node_handle.h>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud.h>
#include <point_cloud_mapping/cloud_io.h>
#include <boost/thread/mutex.hpp>
#include <boost/format.hpp>

class MsgToPCD
{
  protected:
    ros::NodeHandle nh_;
    //dir_ - destination folder for pcds
    std::string input_cloud_topic_, dir_;
    ros::Subscriber cloud_sub_;
    int counter_;
    //for continous saving of pcds
    bool continous_; 
    bool debug_;
    //lock while saving to pcd
    boost::mutex m_lock_;
    boost::format filename_format_;


  public:
  MsgToPCD () :  nh_("~"), counter_(0), debug_(true)
    {
      nh_.param ("input_cloud_topic", input_cloud_topic_, std::string("cloud_pcd"));
      nh_.param ("dir", dir_, std::string(""));       
      nh_.param ("continous", continous_, false);   
      if(debug_)
      ROS_INFO("input_cloud_topic_: %s", input_cloud_topic_.c_str());
      cloud_sub_ = nh_.subscribe (input_cloud_topic_, 1, &MsgToPCD::cloud_cb, this);
    }


    void
      cloud_cb (const sensor_msgs::PointCloudConstPtr& cloud)
    {
      //std::ostringstream filename;
      //filename << dir_ << "cloud_" << time (NULL) << "_" << getpid () << ".pcd";
      //filename << dir_ << "cloud_" <<  << ".pcd";
      filename_format_.parse(std::string("cloud_%f.pcd"));
      std::string filename = dir_ + (filename_format_ %  ros::Time::now().toSec()).str();
      if(debug_)
      ROS_INFO("parameter continous: %d", continous_);
      if ((counter_ == 0) && (!continous_))
      {
        ROS_INFO ("PointCloud message received on %s with %d points. Saving to %s", input_cloud_topic_.c_str (), (int)cloud->points.size (), filename.c_str ());
        cloud_io::savePCDFile (filename.c_str (), *cloud, true);
      }
      if ((counter_ >= 0) && (continous_))
      {
        ROS_INFO ("PointCloud message received on %s with %d points. Saving to %s", input_cloud_topic_.c_str (), (int)cloud->points.size (), filename.c_str ());
        m_lock_.lock ();
        cloud_io::savePCDFile (filename.c_str (), *cloud, true);
        m_lock_.unlock ();
      }
      counter_ ++;
    }


/**
* @brief toggles parameter to start/stop saving pcds
*/

   void updateParametersFromServer ()
    {
      nh_.getParam ("continous", continous_);
      if(debug_)
      ROS_INFO("cont in update: %d", continous_);
    }



    bool 
      spin ()
    {
      ros::Rate loop_rate(1);
      while (nh_.ok())
      {
        ros::spinOnce ();
        if ((counter_ == 1) && (!continous_))
          return true;
        updateParametersFromServer();
    loop_rate.sleep();
      }
      return true;
    }
};


int main (int argc, char* argv[])
{
ros::init (argc, argv, "msg_to_pcd");

MsgToPCD n;
n.spin ();

return (0);
}