abb_joint_downloader_node.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Southwest Research Institute
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * * Neither the name of the Southwest Research Institute, nor the names
16  * of its contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #include "abb_driver/abb_utils.h"
35 
38 
40 {
41  using JointTrajectoryDownloader::init; // so base-class init() stays visible
42 
44 
45 public:
46  bool init(std::string default_ip = "", int default_port = StandardSocketPorts::MOTION)
47  {
48  if (!JointTrajectoryDownloader::init(default_ip, default_port)) // call base-class init()
49  return false;
50 
51  if (ros::param::has("J23_coupled"))
52  ros::param::get("J23_coupled", this->J23_coupled_);
53  else
54  J23_coupled_ = false;
55 
56  return true;
57  }
58 
59  bool transform(const trajectory_msgs::JointTrajectoryPoint& pt_in, trajectory_msgs::JointTrajectoryPoint* pt_out)
60  {
61  // correct for parallel linkage effects, if desired
62  // - use POSITIVE factor for joint->motor correction
63  abb::utils::linkage_transform(pt_in, pt_out, J23_coupled_ ? +1:0 );
64 
65  return true;
66  }
67 
68  bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint& pt, double* rbt_velocity)
69  {
70  *rbt_velocity = 0; // unused by ABB driver
71  return true;
72  }
73 };
74 
75 int main(int argc, char** argv)
76 {
77  // initialize node
78  ros::init(argc, argv, "motion_interface");
79 
80  // launch the default JointTrajectoryDownloader connection/handlers
81  ABB_JointTrajectoryDownloader motionInterface;
82  motionInterface.init();
83  motionInterface.run();
84 
85  return 0;
86 }
ABB_JointTrajectoryDownloader::calc_velocity
bool calc_velocity(const trajectory_msgs::JointTrajectoryPoint &pt, double *rbt_velocity)
Definition: abb_joint_downloader_node.cpp:68
abb::utils::linkage_transform
void linkage_transform(const std::vector< double > &joints_in, std::vector< double > *joints_out, double J23_factor=0)
Corrects for parallel linkage coupling between joints.
Definition: abb_utils.cpp:47
joint_trajectory_downloader.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::param::get
ROSCPP_DECL bool get(const std::string &key, bool &b)
ABB_JointTrajectoryDownloader::J23_coupled_
bool J23_coupled_
Definition: abb_joint_downloader_node.cpp:43
ABB_JointTrajectoryDownloader::transform
bool transform(const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out)
Definition: abb_joint_downloader_node.cpp:59
ABB_JointTrajectoryDownloader::init
bool init(std::string default_ip="", int default_port=StandardSocketPorts::MOTION)
Definition: abb_joint_downloader_node.cpp:46
main
int main(int argc, char **argv)
Definition: abb_joint_downloader_node.cpp:75
abb_utils.h
param_utils.h
industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::run
virtual void run()
industrial::simple_socket::StandardSocketPorts
industrial_robot_client::joint_trajectory_downloader::JointTrajectoryDownloader
ABB_JointTrajectoryDownloader
Definition: abb_joint_downloader_node.cpp:39
ros::param::has
ROSCPP_DECL bool has(const std::string &key)


abb_driver
Author(s): Edward Venator, Jeremy Zoss, Shaun Edwards
autogenerated on Fri Sep 2 2022 02:33:09