00001 /****************************************************************************** 00002 Copyright (c) 2017, Alexander W. Winkler. All rights reserved. 00003 00004 Redistribution and use in source and binary forms, with or without 00005 modification, are permitted provided that the following conditions are met: 00006 00007 * Redistributions of source code must retain the above copyright notice, this 00008 list of conditions and the following disclaimer. 00009 00010 * Redistributions in binary form must reproduce the above copyright notice, 00011 this list of conditions and the following disclaimer in the documentation 00012 and/or other materials provided with the distribution. 00013 00014 * Neither the name of the copyright holder nor the names of its 00015 contributors may be used to endorse or promote products derived from 00016 this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00028 ******************************************************************************/ 00029 00030 #include <xpp_vis/cartesian_joint_converter.h> 00031 00032 #include <ros/node_handle.h> 00033 00034 #include <xpp_msgs/RobotStateJoint.h> 00035 #include <xpp_states/convert.h> 00036 00037 namespace xpp { 00038 00039 CartesianJointConverter::CartesianJointConverter (const InverseKinematics::Ptr& ik, 00040 const std::string& cart_topic, 00041 const std::string& joint_topic) 00042 { 00043 inverse_kinematics_ = ik; 00044 00045 ::ros::NodeHandle n; 00046 cart_state_sub_ = n.subscribe(cart_topic, 1, &CartesianJointConverter::StateCallback, this); 00047 ROS_DEBUG("Subscribed to: %s", cart_state_sub_.getTopic().c_str()); 00048 00049 joint_state_pub_ = n.advertise<xpp_msgs::RobotStateJoint>(joint_topic, 1); 00050 ROS_DEBUG("Publishing to: %s", joint_state_pub_.getTopic().c_str()); 00051 } 00052 00053 void 00054 CartesianJointConverter::StateCallback (const xpp_msgs::RobotStateCartesian& cart_msg) 00055 { 00056 auto cart = Convert::ToXpp(cart_msg); 00057 00058 // transform feet from world -> base frame 00059 Eigen::Matrix3d B_R_W = cart.base_.ang.q.normalized().toRotationMatrix().inverse(); 00060 EndeffectorsPos ee_B(cart.ee_motion_.GetEECount()); 00061 for (auto ee : ee_B.GetEEsOrdered()) 00062 ee_B.at(ee) = B_R_W * (cart.ee_motion_.at(ee).p_ - cart.base_.lin.p_); 00063 00064 Eigen::VectorXd q = inverse_kinematics_->GetAllJointAngles(ee_B).ToVec(); 00065 00066 xpp_msgs::RobotStateJoint joint_msg; 00067 joint_msg.base = cart_msg.base; 00068 joint_msg.ee_contact = cart_msg.ee_contact; 00069 joint_msg.time_from_start = cart_msg.time_from_start; 00070 joint_msg.joint_state.position = std::vector<double>(q.data(), q.data()+q.size()); 00071 // Attention: Not filling joint velocities or torques 00072 00073 joint_state_pub_.publish(joint_msg); 00074 } 00075 00076 } /* namespace xpp */