current_logger.cpp
Go to the documentation of this file.
00001 
00008 #include <carl_tools/current_logger.h>
00009 
00010 using namespace std;
00011 
00012 CurrentLogger::CurrentLogger()
00013 {
00014   // private node handle
00015   ros::NodeHandle private_nh("~");
00016 
00017   // get the id of the calibration marker
00018   private_nh.param<string>("filename", filename, "arm_currents.txt");
00019 
00020   armJointStateSubscriber = n.subscribe("jaco_arm/joint_states", 1, &CurrentLogger::armJointStateCallback, this);
00021 }
00022 
00023 void CurrentLogger::armJointStateCallback(const sensor_msgs::JointState::ConstPtr& msg)
00024 {
00025   ofstream outputFile;
00026   outputFile.open(filename.c_str(), ios::out | ios::app);
00027   outputFile << ros::Time::now().toSec() << ",";
00028   for (unsigned int i = 0; i < msg->effort.size(); i ++)
00029   {
00030     if (i < msg->effort.size() - 1)
00031       outputFile << msg->effort[i] << ",";
00032     else
00033       outputFile << msg->effort[i];
00034   }
00035   outputFile << "\n";
00036   outputFile.close();
00037 }
00038 
00039 int main(int argc, char **argv)
00040 {
00041   ros::init(argc, argv, "current_logger");
00042 
00043   CurrentLogger cl;
00044 
00045   ros::spin();
00046 }


carl_tools
Author(s): Russell Toris , David Kent
autogenerated on Thu Jun 6 2019 21:10:06