joint_position_to_joint_trajectory.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2015-2017, the ypspur_ros authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 
00032 #include <sensor_msgs/JointState.h>
00033 #include <trajectory_msgs/JointTrajectory.h>
00034 #include <ypspur_ros/JointPositionControl.h>
00035 
00036 #include <map>
00037 #include <string>
00038 
00039 #include <compatibility.h>
00040 
00041 class ConvertNode
00042 {
00043 private:
00044   ros::NodeHandle nh_;
00045   ros::NodeHandle pnh_;
00046   ros::Subscriber sub_joint_;
00047   ros::Subscriber sub_joint_state_;
00048   ros::Publisher pub_joint_;
00049 
00050   std::map<std::string, double> state_;
00051 
00052   double accel_;
00053   bool skip_same_;
00054 
00055   void cbJointState(const sensor_msgs::JointState::ConstPtr& msg)
00056   {
00057     for (size_t i = 0; i < msg->name.size(); i++)
00058     {
00059       state_[msg->name[i]] = msg->position[i];
00060     }
00061   }
00062   ypspur_ros::JointPositionControl cmd_prev;
00063   void cbJointPosition(const ypspur_ros::JointPositionControl::ConstPtr& msg)
00064   {
00065     while (true)
00066     {
00067       if (msg->joint_names.size() != cmd_prev.joint_names.size())
00068         break;
00069       {
00070         bool eq = true;
00071         for (unsigned int i = 0; i < msg->joint_names.size(); i++)
00072         {
00073           if (msg->joint_names[i].compare(cmd_prev.joint_names[i]) != 0)
00074             eq = false;
00075         }
00076         if (!eq)
00077           break;
00078       }
00079       if (msg->positions.size() != cmd_prev.positions.size())
00080         break;
00081       {
00082         bool eq = true;
00083         for (unsigned int i = 0; i < msg->positions.size(); i++)
00084         {
00085           if (msg->positions[i] != cmd_prev.positions[i])
00086             eq = false;
00087         }
00088         if (!eq)
00089           break;
00090       }
00091       if (msg->velocities.size() != cmd_prev.velocities.size())
00092         break;
00093       {
00094         bool eq = true;
00095         for (unsigned int i = 0; i < msg->velocities.size(); i++)
00096         {
00097           if (msg->velocities[i] != cmd_prev.velocities[i])
00098             eq = false;
00099         }
00100         if (!eq)
00101           break;
00102       }
00103       if (msg->accelerations.size() != cmd_prev.accelerations.size())
00104         break;
00105       {
00106         bool eq = true;
00107         for (unsigned int i = 0; i < msg->accelerations.size(); i++)
00108         {
00109           if (msg->accelerations[i] != cmd_prev.accelerations[i])
00110             eq = false;
00111         }
00112         if (!eq)
00113           break;
00114       }
00115       return;
00116     }
00117     cmd_prev = *msg;
00118 
00119     trajectory_msgs::JointTrajectory cmd;
00120     cmd.header = msg->header;
00121     cmd.joint_names = msg->joint_names;
00122     cmd.points.resize(1);
00123     cmd.points[0].velocities.resize(msg->positions.size());
00124     cmd.points[0].positions = msg->positions;
00125     cmd.points[0].accelerations.resize(msg->positions.size());
00126 
00127     float t_max = 0;
00128     int i = 0;
00129     for (auto& p : msg->positions)
00130     {
00131       float t = fabs(p - state_[msg->joint_names[i]]) / msg->velocities[i];
00132       if (t_max < t)
00133         t_max = t;
00134 
00135       i++;
00136     }
00137     cmd.points[0].time_from_start = ros::Duration(t_max);
00138 
00139     pub_joint_.publish(cmd);
00140   }
00141 
00142 public:
00143   ConvertNode()
00144     : nh_()
00145     , pnh_("~")
00146   {
00147     sub_joint_ = compat::subscribe(
00148         nh_, "joint_position",
00149         pnh_, "joint_position", 5, &ConvertNode::cbJointPosition, this);
00150     sub_joint_state_ = compat::subscribe(
00151         nh_, "joint_states",
00152         pnh_, "joint", 5, &ConvertNode::cbJointState, this);
00153     pub_joint_ = compat::advertise<trajectory_msgs::JointTrajectory>(
00154         nh_, "joint_trajectory",
00155         pnh_, "joint_trajectory", 5, false);
00156 
00157     pnh_.param("accel", accel_, 0.3);
00158     pnh_.param("skip_same", skip_same_, true);
00159   }
00160 };
00161 
00162 int main(int argc, char* argv[])
00163 {
00164   ros::init(argc, argv, "joint_position_to_joint_trajectory");
00165 
00166   ConvertNode conv;
00167   ros::spin();
00168 
00169   return 0;
00170 }


ypspur_ros
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 6 2019 20:19:02