Go to the documentation of this file.00001
00027 #include "sr_self_test/test_joint_movement.hpp"
00028 #include <stdio.h>
00029 #include "boost/iostreams/device/file_descriptor.hpp"
00030 #include "boost/iostreams/stream.hpp"
00031
00032
00033 namespace shadow_robot
00034 {
00035 TestJointMovement::TestJointMovement(std::string joint_name, shadowrobot::HandCommander* hand_commander)
00036 : mse(0.0), nh_tilde_("~")
00037 {
00038 joint_name_ = joint_name;
00039
00040
00041 mse_sub_ = nh_tilde_.subscribe("mse_out", 1, &TestJointMovement::mse_cb_, this);
00042
00043
00044 std::string img_path;
00045 nh_tilde_.getParam("image_path", img_path);
00046
00047 mvt_from_img_.reset(new shadowrobot::MovementFromImage(img_path) );
00048
00049 double publish_rate;
00050 unsigned int repetition, nb_mvt_step;
00051 publish_rate = 100.0;
00052 repetition = 1;
00053 nb_mvt_step = 10000;
00054
00055 if( hand_commander != NULL )
00056 hand_commander_.reset(hand_commander);
00057 else
00058 hand_commander_.reset(new shadowrobot::HandCommander());
00059
00060 std::string controller_state_topic = hand_commander_->get_controller_state_topic(joint_name);
00061 std::string controller_state_topic_type = get_ROS_topic_type(controller_state_topic);
00062 std::string controller_type = "";
00063 if(controller_state_topic_type.compare("sr_robot_msgs/JointControllerState") == 0)
00064 {
00065 controller_type = "sr";
00066 }
00067
00068 mvt_pub_.reset(new shadowrobot::MovementPublisher(joint_name, publish_rate, repetition,
00069 nb_mvt_step, controller_type, false,
00070 hand_commander ));
00071 mvt_pub_->add_movement( *mvt_from_img_.get() );
00072
00073 if(controller_type.compare("sr") == 0)
00074 {
00075 sr_sub_state_ = nh_tilde_.subscribe( mvt_pub_->get_subscriber_topic(), nb_mvt_step,
00076 &TestJointMovement::sr_state_cb_, this );
00077 }
00078 else
00079 {
00080 sub_state_ = nh_tilde_.subscribe( mvt_pub_->get_subscriber_topic(), nb_mvt_step,
00081 &TestJointMovement::state_cb_, this );
00082 }
00083
00084 mvt_pub_->start();
00085 }
00086
00087 void TestJointMovement::sr_state_cb_(const sr_robot_msgs::JointControllerState::ConstPtr& msg)
00088 {
00089 values[joint_name_ +" position"].push_back(msg->process_value);
00090 values[joint_name_ +" target"].push_back(msg->set_point);
00091 values[joint_name_ +" error"].push_back(msg->error);
00092 }
00093
00094 void TestJointMovement::state_cb_(const control_msgs::JointControllerState::ConstPtr& msg)
00095 {
00096 values[joint_name_ +" position"].push_back(msg->process_value);
00097 values[joint_name_ +" target"].push_back(msg->set_point);
00098 values[joint_name_ +" error"].push_back(msg->error);
00099 }
00100
00101 void TestJointMovement::mse_cb_(const std_msgs::Float64::ConstPtr& msg)
00102 {
00103 mse = msg->data;
00104
00105
00106 mse_sub_.shutdown();
00107 sub_state_.shutdown();
00108 }
00109
00110 std::string TestJointMovement::get_ROS_topic_type(std::string topic_name)
00111 {
00112 typedef boost::iostreams::file_descriptor_source boost_fd;
00113 typedef boost::iostreams::stream<boost_fd> boost_stream;
00114
00115 FILE *myfile;
00116 std::string cmd;
00117
00118 cmd = "rostopic type " + topic_name;
00119
00120
00121 if(!(myfile = popen(cmd.c_str(), "r")))
00122 {
00123 ROS_ERROR_STREAM("Command failed: " << cmd);
00124 }
00125
00126 boost_fd fd(fileno(myfile), boost::iostreams::never_close_handle);
00127 boost_stream stream(fd);
00128
00129 std::string topic_type;
00130 if( !std::getline(stream,topic_type))
00131 {
00132 ROS_ERROR_STREAM("Could nod read line from get_ROS_topic_type command");
00133 }
00134
00135 pclose(myfile);
00136 return topic_type;
00137 }
00138 }
00139
00140
00141
00142
00143
00144
00145