test_trajectory_command_sine_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <vector>
19 #include <string>
20 
21 #include <ros/ros.h>
22 #include <std_msgs/Float64.h>
23 #include <trajectory_msgs/JointTrajectory.h>
24 #include <kdl/jntarray.hpp>
26 
28 {
29 public:
31  {
32  dof_ = 2;
33  idx_ = 0;
34 
35  q_.resize(dof_);
36  KDL::SetToZero(q_);
37  q_dot_.resize(dof_);
38  KDL::SetToZero(q_dot_);
39  simpson_q_.resize(dof_);
40  KDL::SetToZero(simpson_q_);
41  euler_q_.resize(dof_);
42  KDL::SetToZero(euler_q_);
44  KDL::SetToZero(derived_simpson_q_dot_);
45 
47  trajectory_pub_ = nh_.advertise<trajectory_msgs::JointTrajectory>("joint_trajectory_controller/command", 1);
48 
49  output_q_pub_ = nh_.advertise<std_msgs::Float64>("integrator_debug/q", 1);
50  output_q_dot_pub_ = nh_.advertise<std_msgs::Float64>("integrator_debug/q_dot", 1);
51  output_simpson_q_pub_ = nh_.advertise<std_msgs::Float64>("integrator_debug/simpson_q", 1);
52  output_euler_q_pub_ = nh_.advertise<std_msgs::Float64>("integrator_debug/euler_q", 1);
53  output_derived_simpson_q_dot_pub_ = nh_.advertise<std_msgs::Float64>("integrator_debug/derived_simpson_q_dot", 1);
54 
55  ros::Duration(1.0).sleep();
56  }
57 
58 
60  {}
61 
62  void run()
63  {
64  ros::Rate r(100.0);
65 
66  ros::Time time = ros::Time::now();
67  ros::Time last_update_time = time;
68  ros::Duration period = time - last_update_time;
69  ros::Time start_time = time;
70  double x = time.toSec() - start_time.toSec();
71  double old_pos = -99;
72 
73  // double a = 0.6, b = 1.0, c = 0, d = 0; // lwa4d
74  double a = 0.6, b = 0.4, c = 0, d = 0; // torso_2dof
75  euler_q_(idx_) = a*sin(b*x+c) + d; // correct initial value
76 
77  trajectory_msgs::JointTrajectoryPoint traj_point;
78  traj_point.positions.assign(dof_, 0.0);
79  // traj_point.velocities.assign(dof_,0.0);
80 
81  std::vector<std::string> joint_names;
82  // joint_names.push_back("arm_1_joint");
83  // joint_names.push_back("arm_2_joint");
84  // joint_names.push_back("arm_3_joint");
85  // joint_names.push_back("arm_4_joint");
86  // joint_names.push_back("arm_5_joint");
87  // joint_names.push_back("arm_6_joint");
88  // joint_names.push_back("arm_7_joint");
89  joint_names.push_back("torso_2_joint");
90  joint_names.push_back("torso_3_joint");
91 
92  while (ros::ok())
93  {
94  time = ros::Time::now();
95  period = time - last_update_time;
96  last_update_time = time;
97  x = time.toSec() - start_time.toSec();
98 
99  std::vector<double> next_q;
100  std::vector<double> next_q_dot;
101 
102  q_(idx_) = a*sin(b*x+c) + d;
103  q_dot_(idx_) = a*b*cos(b*x+c);
104 
105  if (integrator_->updateIntegration(q_dot_, q_, next_q, next_q_dot))
106  {
107  simpson_q_(idx_) = next_q[idx_];
108  // q_dot_(idx_) = next_q_dot[idx_];
109  }
110 
111  euler_q_(idx_) += q_dot_(idx_) * period.toSec();
112 
113  traj_point.positions[idx_] = q_(idx_);
114  // traj_point.velocities[idx_] = q_dot_(idx_);
115  // traj_point.time_from_start = ros::Duration(0.5); // should be as small as possible
116  traj_point.time_from_start = ros::Duration(period.toSec()); // seems to be a good value
117  // traj_point.time_from_start = ros::Duration(0.1 * period.toSec()); // does not make a difference anymore
119 
120  trajectory_msgs::JointTrajectory traj_msg;
121  traj_msg.points.push_back(traj_point);
122  traj_msg.joint_names = joint_names;
123  // traj_msg.header.stamp = ros::Time::now(); //now or none - does not make a difference
124 
125 
126  std_msgs::Float64 q_msg; // cos
127  q_msg.data = q_(idx_);
128  std_msgs::Float64 q_dot_msg; // sin
129  q_dot_msg.data = q_dot_(idx_);
130  std_msgs::Float64 simpson_q_msg;
131  simpson_q_msg.data = simpson_q_(idx_);
132  std_msgs::Float64 euler_q_msg;
133  euler_q_msg.data = euler_q_(idx_);
134  std_msgs::Float64 derived_simpson_q_dot_msg;
135  derived_simpson_q_dot_msg.data = derived_simpson_q_dot_(idx_);
136 
137  output_q_pub_.publish(q_msg);
138  output_q_dot_pub_.publish(q_dot_msg);
139  output_simpson_q_pub_.publish(simpson_q_msg);
140  output_euler_q_pub_.publish(euler_q_msg);
141  output_derived_simpson_q_dot_pub_.publish(derived_simpson_q_dot_msg);
142 
143  trajectory_pub_.publish(traj_msg);
144 
145  ros::spinOnce();
146  r.sleep();
147  }
148  }
149 
150 
153 
159 
160  KDL::JntArray q_;
161  KDL::JntArray q_dot_;
162  KDL::JntArray simpson_q_;
163  KDL::JntArray euler_q_;
164  KDL::JntArray derived_simpson_q_dot_;
165 
167 
168  unsigned int dof_;
169  unsigned int idx_;
170 };
171 
172 
173 
174 int main(int argc, char **argv)
175 {
176  ros::init(argc, argv, "test_trajectory_command_execution_node");
177 
179  tcet.run();
180  ros::spin();
181  return 0;
182 }
TrajectoryCommandExecutionTester::output_euler_q_pub_
ros::Publisher output_euler_q_pub_
Definition: test_trajectory_command_sine_node.cpp:157
ros::Publisher
boost::shared_ptr< SimpsonIntegrator >
TrajectoryCommandExecutionTester::derived_simpson_q_dot_
KDL::JntArray derived_simpson_q_dot_
Definition: test_trajectory_command_sine_node.cpp:164
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TrajectoryCommandExecutionTester::q_dot_
KDL::JntArray q_dot_
Definition: test_trajectory_command_sine_node.cpp:161
TrajectoryCommandExecutionTester::output_derived_simpson_q_dot_pub_
ros::Publisher output_derived_simpson_q_dot_pub_
Definition: test_trajectory_command_sine_node.cpp:158
ros.h
r
r
TrajectoryCommandExecutionTester::run
void run()
Definition: test_trajectory_command_sine_node.cpp:62
ros::spinOnce
ROSCPP_DECL void spinOnce()
TrajectoryCommandExecutionTester::euler_q_
KDL::JntArray euler_q_
Definition: test_trajectory_command_sine_node.cpp:163
TimeBase< Time, Duration >::toSec
double toSec() const
SimpsonIntegrator
Definition: simpson_integrator.h:29
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
TrajectoryCommandExecutionTester::dof_
unsigned int dof_
Definition: test_trajectory_command_sine_node.cpp:168
TrajectoryCommandExecutionTester
Definition: test_trajectory_command_sine_node.cpp:27
TrajectoryCommandExecutionTester::simpson_q_
KDL::JntArray simpson_q_
Definition: test_trajectory_command_sine_node.cpp:162
TrajectoryCommandExecutionTester::output_q_pub_
ros::Publisher output_q_pub_
Definition: test_trajectory_command_sine_node.cpp:154
simpson_integrator.h
main
int main(int argc, char **argv)
Definition: test_trajectory_command_sine_node.cpp:174
TrajectoryCommandExecutionTester::~TrajectoryCommandExecutionTester
~TrajectoryCommandExecutionTester()
Definition: test_trajectory_command_sine_node.cpp:59
setup.d
d
Definition: setup.py:6
TrajectoryCommandExecutionTester::q_
KDL::JntArray q_
Definition: test_trajectory_command_sine_node.cpp:160
TrajectoryCommandExecutionTester::output_simpson_q_pub_
ros::Publisher output_simpson_q_pub_
Definition: test_trajectory_command_sine_node.cpp:156
TrajectoryCommandExecutionTester::output_q_dot_pub_
ros::Publisher output_q_dot_pub_
Definition: test_trajectory_command_sine_node.cpp:155
ros::Time
TrajectoryCommandExecutionTester::nh_
ros::NodeHandle nh_
Definition: test_trajectory_command_sine_node.cpp:151
ros::Rate
ros::spin
ROSCPP_DECL void spin()
ros::Duration::sleep
bool sleep() const
DurationBase< Duration >::toSec
double toSec() const
TrajectoryCommandExecutionTester::idx_
unsigned int idx_
Definition: test_trajectory_command_sine_node.cpp:169
ros::Duration
TrajectoryCommandExecutionTester::TrajectoryCommandExecutionTester
TrajectoryCommandExecutionTester()
Definition: test_trajectory_command_sine_node.cpp:30
TrajectoryCommandExecutionTester::integrator_
boost::shared_ptr< SimpsonIntegrator > integrator_
Definition: test_trajectory_command_sine_node.cpp:166
ros::NodeHandle
TrajectoryCommandExecutionTester::trajectory_pub_
ros::Publisher trajectory_pub_
Definition: test_trajectory_command_sine_node.cpp:152
ros::Time::now
static Time now()


cob_twist_controller
Author(s): Felix Messmer , Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43