Main Page
Namespaces
Namespace List
Namespace Members
All
Functions
Classes
Class List
Class Hierarchy
Class Members
All
Functions
Variables
Files
File List
File Members
All
Functions
src
fanuc_joint_streamer_node.cpp
Go to the documentation of this file.
1
/*
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2013-2015, TU Delft Robotics 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
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of the TU Delft Robotics Institute nor the names
18
* of its contributors may be used to endorse or promote products
19
* derived from this software without specific prior written
20
* permission.
21
*
22
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
* POSSIBILITY OF SUCH DAMAGE.
34
*
35
*
36
* Author: G.A. vd. Hoorn - TU Delft Robotics Institute
37
*/
38
39
#include <
fanuc_driver/fanuc_utils.h
>
40
41
#include <
industrial_robot_client/joint_trajectory_streamer.h
>
42
43
#include <stdexcept>
44
45
46
using
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer
;
47
48
49
class
Fanuc_JointTrajectoryStreamer
:
public
JointTrajectoryStreamer
50
{
51
int
J23_factor_
;
52
53
54
public
:
55
Fanuc_JointTrajectoryStreamer
() :
JointTrajectoryStreamer
(),
J23_factor_
(0)
56
{
57
if
(!
ros::param::has
(
"J23_factor"
))
58
{
59
ROS_FATAL
(
"Joint 2-3 linkage factor parameter not supplied."
);
60
throw
std::runtime_error(
"Cannot find required parameter 'J23_factor' on parameter server."
);
61
}
62
63
ros::param::get
(
"J23_factor"
, this->J23_factor_);
64
}
65
66
67
virtual
~Fanuc_JointTrajectoryStreamer
() {}
68
69
70
bool
transform
(
const
trajectory_msgs::JointTrajectoryPoint& pt_in,
71
trajectory_msgs::JointTrajectoryPoint* pt_out)
72
{
73
// sending points back to the Fanuc, so invert factor
74
fanuc::utils::linkage_transform
(pt_in, pt_out, -
J23_factor_
);
75
76
return
true
;
77
}
78
};
79
80
81
int
main
(
int
argc,
char
** argv)
82
{
83
// initialize node
84
ros::init
(argc, argv,
"motion_interface"
);
85
86
// launch the default JointTrajectoryStreamer connection/handlers
87
Fanuc_JointTrajectoryStreamer
motionInterface;
88
89
motionInterface.
init
();
90
motionInterface.
run
();
91
92
return
0;
93
}
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer
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)
Fanuc_JointTrajectoryStreamer
Definition:
fanuc_joint_streamer_node.cpp:49
Fanuc_JointTrajectoryStreamer::J23_factor_
int J23_factor_
Definition:
fanuc_joint_streamer_node.cpp:51
fanuc::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:
fanuc_utils.cpp:60
Fanuc_JointTrajectoryStreamer::transform
bool transform(const trajectory_msgs::JointTrajectoryPoint &pt_in, trajectory_msgs::JointTrajectoryPoint *pt_out)
Definition:
fanuc_joint_streamer_node.cpp:70
Fanuc_JointTrajectoryStreamer::~Fanuc_JointTrajectoryStreamer
virtual ~Fanuc_JointTrajectoryStreamer()
Definition:
fanuc_joint_streamer_node.cpp:67
fanuc_utils.h
industrial_robot_client::joint_trajectory_interface::JointTrajectoryInterface::run
virtual void run()
main
int main(int argc, char **argv)
Definition:
fanuc_joint_streamer_node.cpp:81
joint_trajectory_streamer.h
industrial_robot_client::joint_trajectory_streamer::JointTrajectoryStreamer::init
virtual bool init(SmplMsgConnection *connection)
ROS_FATAL
#define ROS_FATAL(...)
ros::param::has
ROSCPP_DECL bool has(const std::string &key)
Fanuc_JointTrajectoryStreamer::Fanuc_JointTrajectoryStreamer
Fanuc_JointTrajectoryStreamer()
Definition:
fanuc_joint_streamer_node.cpp:55
fanuc_driver
Author(s): G.A. vd. Hoorn (TU Delft Robotics Institute)
autogenerated on Thu Feb 20 2025 04:09:12