Go to the documentation of this file.00001
00027 #include <ros/ros.h>
00028
00029
00030 #include <map>
00031 #include <string>
00032 #include <vector>
00033
00034
00035 #include <std_msgs/Float64.h>
00036
00037 class TargetSender
00038 {
00039 public:
00045 TargetSender()
00046 {
00051 static const std::string joints[20] = {"ffj0", "ffj3", "ffj4",
00052 "mfj0", "mfj3", "mfj4",
00053 "rfj0", "rfj3", "rfj4",
00054 "lfj0", "lfj3", "lfj4", "lfj5",
00055 "thj1", "thj2", "thj3", "thj4", "thj5",
00056 "wrj1", "wrj2"};
00057
00058 static const std::string prefix = "/sh_";
00059 static const std::string suffix = "_position_controller/command";
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069 for (unsigned int index_joint = 0; index_joint < 20; ++index_joint)
00070 {
00071 std::string joint_tmp = joints[index_joint];
00072 publisher_map_[joint_tmp] = node_handle_.advertise<std_msgs::Float64>(prefix + joint_tmp + suffix, 2);
00073 }
00074 };
00075
00076 ~TargetSender()
00077 {
00078 };
00079
00088 bool sendupdate(std::string joint_name, double target)
00089 {
00090
00091
00092 std::map<std::string, ros::Publisher>::iterator publisher_iterator;
00093 publisher_iterator = publisher_map_.find(joint_name);
00094
00095 if (publisher_iterator == publisher_map_.end())
00096 {
00097 ROS_WARN_STREAM("Joint " << joint_name << " not found.");
00098 return false;
00099 }
00100
00101
00102
00103 std_msgs::Float64 msg_to_send;
00104 msg_to_send.data = target * 3.14159 / 360.0;
00105 publisher_iterator->second.publish(msg_to_send);
00106
00107 return true;
00108 };
00109
00110 protected:
00112 std::map <std::string, ros::Publisher> publisher_map_;
00114 ros::NodeHandle node_handle_;
00115 };
00116
00117
00130 int main(int argc, char **argv)
00131 {
00132
00133 ros::init(argc, argv, "send_targets");
00134
00135
00136 TargetSender target_sender = TargetSender();
00137
00138
00139 static const unsigned int length_targets = 1000;
00140 std::vector<double> targets;
00141
00142 for (unsigned int i = 0; i < length_targets; ++i)
00143 {
00144 double target = static_cast<double>(i) / 1000.0 * 90.0;
00145 targets.push_back(target);
00146 }
00147
00148
00149 unsigned int step = 0;
00150 while (ros::ok())
00151 {
00152 target_sender.sendupdate("ffj3", targets[step % length_targets]);
00153 usleep(10000);
00154
00155 ++step;
00156 }
00157
00158 return 0;
00159 }
00160
00161
00162
00163
00164
00165