cartesian_joint_converter.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
31 
32 #include <ros/node_handle.h>
33 
34 #include <xpp_msgs/RobotStateJoint.h>
35 #include <xpp_states/convert.h>
36 
37 namespace xpp {
38 
40  const std::string& cart_topic,
41  const std::string& joint_topic)
42 {
44 
47  ROS_DEBUG("Subscribed to: %s", cart_state_sub_.getTopic().c_str());
48 
49  joint_state_pub_ = n.advertise<xpp_msgs::RobotStateJoint>(joint_topic, 1);
50  ROS_DEBUG("Publishing to: %s", joint_state_pub_.getTopic().c_str());
51 }
52 
53 void
54 CartesianJointConverter::StateCallback (const xpp_msgs::RobotStateCartesian& cart_msg)
55 {
56  auto cart = Convert::ToXpp(cart_msg);
57 
58  // transform feet from world -> base frame
59  Eigen::Matrix3d B_R_W = cart.base_.ang.q.normalized().toRotationMatrix().inverse();
60  EndeffectorsPos ee_B(cart.ee_motion_.GetEECount());
61  for (auto ee : ee_B.GetEEsOrdered())
62  ee_B.at(ee) = B_R_W * (cart.ee_motion_.at(ee).p_ - cart.base_.lin.p_);
63 
64  Eigen::VectorXd q = inverse_kinematics_->GetAllJointAngles(ee_B).ToVec();
65 
66  xpp_msgs::RobotStateJoint joint_msg;
67  joint_msg.base = cart_msg.base;
68  joint_msg.ee_contact = cart_msg.ee_contact;
69  joint_msg.time_from_start = cart_msg.time_from_start;
70  joint_msg.joint_state.position = std::vector<double>(q.data(), q.data()+q.size());
71  // Attention: Not filling joint velocities or torques
72 
73  joint_state_pub_.publish(joint_msg);
74 }
75 
76 } /* namespace xpp */
cartesian_joint_converter.h
node_handle.h
ros::Subscriber::getTopic
std::string getTopic() const
ROS_DEBUG
#define ROS_DEBUG(...)
xpp::CartesianJointConverter::CartesianJointConverter
CartesianJointConverter(const InverseKinematics::Ptr &ik, const std::string &cart_topic, const std::string &joint_topic)
Creates a converter initializing the subscriber and publisher.
Definition: cartesian_joint_converter.cc:66
xpp::Convert::ToXpp
static Eigen::Quaterniond ToXpp(const geometry_msgs::Quaternion ros)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
xpp::CartesianJointConverter::inverse_kinematics_
InverseKinematics::Ptr inverse_kinematics_
Definition: cartesian_joint_converter.h:124
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::NodeHandle
xpp
xpp::CartesianJointConverter::cart_state_sub_
ros::Subscriber cart_state_sub_
Definition: cartesian_joint_converter.h:121
ros::Publisher::getTopic
std::string getTopic() const
EndeffectorsPos
Endeffectors< Eigen::Vector3d > EndeffectorsPos
convert.h
xpp::CartesianJointConverter::joint_state_pub_
ros::Publisher joint_state_pub_
Definition: cartesian_joint_converter.h:122
xpp::InverseKinematics::Ptr
std::shared_ptr< InverseKinematics > Ptr
Definition: inverse_kinematics.h:104
xpp::CartesianJointConverter::StateCallback
void StateCallback(const xpp_msgs::RobotStateCartesian &msg)
Definition: cartesian_joint_converter.cc:81


xpp_vis
Author(s): Alexander W. Winkler
autogenerated on Wed Mar 2 2022 01:14:16