laser_scanner_traj_controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
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 Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #pragma once
36 
37 #include <ros/node_handle.h>
38 
40 #include <control_toolbox/pid.h>
41 //#include <robot_mechanism_controllers/joint_position_smoothing_controller.h>
42 
44 #include <tf/tf.h>
45 
46 #include "filters/filter_chain.hpp"
47 
48 // Messages
49 #include <pr2_msgs/LaserScannerSignal.h>
50 #include <pr2_msgs/PeriodicCmd.h>
51 #include <pr2_mechanism_controllers/TrackLinkCmd.h>
52 #include <pr2_msgs/LaserTrajCmd.h>
53 
54 // Services
55 #include <pr2_mechanism_controllers/SetProfile.h>
56 #include <pr2_msgs/SetPeriodicCmd.h>
57 #include <pr2_msgs/SetLaserTrajCmd.h>
58 
59 #include <boost/thread/mutex.hpp>
61 
62 namespace controller
63 {
64 
65 class LaserScannerTrajController
66 {
67 public:
70 
72 
73  virtual void update() ;
74 
75  bool setPeriodicCmd(const pr2_msgs::PeriodicCmd& cmd) ;
76 
77  bool setTrajCmd(const pr2_msgs::LaserTrajCmd& traj_cmd) ;
78 
79  //bool setTrackLinkCmd(const pr2_mechanism_controllers::TrackLinkCmd& track_link_cmd) ;
80 
81  bool setTrajectory(const std::vector<trajectory::Trajectory::TPoint>& traj_points,
82  double max_rate, double max_acc, std::string interp ) ;
83 
85  inline double getCurProfileTime() ;
87  inline double getProfileDuration() ;
89  inline int getCurProfileSegment() ;
90 
91 private:
92 
94  pr2_mechanism_model::JointState *joint_state_ ; // Need this to check the calibrated flag on the joint
95 
96  boost::mutex traj_lock_ ; // Mutex for traj_
97  trajectory::Trajectory traj_ ; // Stores the current trajectory being executed
98 
99  tf::Vector3 track_point_ ;
100 
101  std::string name_ ; // The controller name. Used for ROS_INFO Messages
102 
103  ros::Time traj_start_time_ ; // The time that the trajectory was started (in seconds)
104  double traj_duration_ ; // The length of the current profile (in seconds)
105 
106 
107  double max_rate_ ; // Max allowable rate/velocity
108  double max_acc_ ; // Max allowable acceleration
109 
110  // Control loop state
111  control_toolbox::Pid pid_controller_ ; // Position PID Controller
112  filters::FilterChain<double> d_error_filter_chain_; // Filter on derivative term of error
113  ros::Time last_time_ ; // The previous time at which the control loop was run
114  double last_error_ ; // Error for the previous time at which the control loop was run
115  double tracking_offset_ ; // Position cmd generated by the track_link code
116  double traj_command_ ; // Position cmd generated by the trajectory code
117 };
118 
120 {
121 public:
124 
125  void update() ;
126 
128 
129  // Message Callbacks
130  void setPeriodicCmd(const pr2_msgs::PeriodicCmdConstPtr &cmd);
131  void setTrajCmd(const pr2_msgs::LaserTrajCmdConstPtr &traj_cmd);
132  //void setTrackLinkCmd() ;
133  bool setPeriodicSrv(pr2_msgs::SetPeriodicCmd::Request &req,
134  pr2_msgs::SetPeriodicCmd::Response &res);
135  bool setTrajSrv(pr2_msgs::SetLaserTrajCmd::Request &req,
136  pr2_msgs::SetLaserTrajCmd::Response &res);
137 
138 
139 private:
145 
148  std::string service_prefix_ ;
149 
150  int prev_profile_segment_ ;
151 
152  pr2_mechanism_controllers::TrackLinkCmd track_link_cmd_ ;
153 
154  pr2_msgs::LaserScannerSignal m_scanner_signal_ ;
155  bool need_to_send_msg_ ;
157 };
158 
159 }
controller::LaserScannerTrajControllerNode::need_to_send_msg_
bool need_to_send_msg_
Tracks whether we still need to send out the m_scanner_signal_ message.
Definition: laser_scanner_traj_controller.h:187
controller::LaserScannerTrajController::traj_
trajectory::Trajectory traj_
Definition: laser_scanner_traj_controller.h:161
controller::LaserScannerTrajController::track_point_
tf::Vector3 track_point_
Definition: laser_scanner_traj_controller.h:163
realtime_publisher.h
node_handle.h
pr2_mechanism_model::JointState
controller::LaserScannerTrajController::traj_lock_
boost::mutex traj_lock_
Definition: laser_scanner_traj_controller.h:160
trajectory.h
controller::LaserScannerTrajController::max_rate_
double max_rate_
Definition: laser_scanner_traj_controller.h:171
send_laser_traj_cmd_ms2.cmd
cmd
Definition: send_laser_traj_cmd_ms2.py:28
controller::LaserScannerTrajControllerNode::sub_set_periodic_cmd_
ros::Subscriber sub_set_periodic_cmd_
Definition: laser_scanner_traj_controller.h:173
controller::LaserScannerTrajController::traj_duration_
double traj_duration_
Definition: laser_scanner_traj_controller.h:168
controller::LaserScannerTrajControllerNode::node_
ros::NodeHandle node_
Definition: laser_scanner_traj_controller.h:172
trajectory::Trajectory
Definition: trajectory.h:56
controller::LaserScannerTrajControllerNode::prev_profile_segment_
int prev_profile_segment_
The segment in the current profile when update() was last called.
Definition: laser_scanner_traj_controller.h:182
controller::LaserScannerTrajController::max_acc_
double max_acc_
Definition: laser_scanner_traj_controller.h:172
controller::LaserScannerTrajControllerNode::setTrajSrv
bool setTrajSrv(pr2_msgs::SetLaserTrajCmd::Request &req, pr2_msgs::SetLaserTrajCmd::Response &res)
Definition: laser_scanner_traj_controller.cpp:507
controller::LaserScannerTrajController::getProfileDuration
double getProfileDuration()
Returns the length (in seconds) of our current profile.
Definition: laser_scanner_traj_controller.cpp:216
controller::LaserScannerTrajController::last_error_
double last_error_
Definition: laser_scanner_traj_controller.h:178
controller::LaserScannerTrajControllerNode::LaserScannerTrajControllerNode
LaserScannerTrajControllerNode()
Definition: laser_scanner_traj_controller.cpp:400
controller::LaserScannerTrajControllerNode::track_link_cmd_
pr2_mechanism_controllers::TrackLinkCmd track_link_cmd_
Definition: laser_scanner_traj_controller.h:184
ros::ServiceServer
controller::LaserScannerTrajController::d_error_filter_chain_
filters::FilterChain< double > d_error_filter_chain_
Definition: laser_scanner_traj_controller.h:176
filters::FilterChain< double >
controller::LaserScannerTrajControllerNode::publisher_
realtime_tools::RealtimePublisher< pr2_msgs::LaserScannerSignal > * publisher_
Publishes the m_scanner_signal msg from the update() realtime loop.
Definition: laser_scanner_traj_controller.h:188
realtime_tools::RealtimePublisher< pr2_msgs::LaserScannerSignal >
controller::LaserScannerTrajController::joint_state_
pr2_mechanism_model::JointState * joint_state_
Definition: laser_scanner_traj_controller.h:158
controller::LaserScannerTrajController::pid_controller_
control_toolbox::Pid pid_controller_
Definition: laser_scanner_traj_controller.h:175
controller.h
controller
pr2_mechanism_model::RobotState
controller::LaserScannerTrajController
Definition: laser_scanner_traj_controller.h:97
controller::LaserScannerTrajControllerNode
Definition: laser_scanner_traj_controller.h:151
controller::LaserScannerTrajController::traj_start_time_
ros::Time traj_start_time_
Definition: laser_scanner_traj_controller.h:167
controller::LaserScannerTrajControllerNode::setPeriodicSrv
bool setPeriodicSrv(pr2_msgs::SetPeriodicCmd::Request &req, pr2_msgs::SetPeriodicCmd::Response &res)
Definition: laser_scanner_traj_controller.cpp:486
controller::LaserScannerTrajController::init
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: laser_scanner_traj_controller.cpp:58
controller::LaserScannerTrajControllerNode::~LaserScannerTrajControllerNode
~LaserScannerTrajControllerNode()
Definition: laser_scanner_traj_controller.cpp:407
controller::LaserScannerTrajController::robot_
pr2_mechanism_model::RobotState * robot_
Definition: laser_scanner_traj_controller.h:157
controller::LaserScannerTrajController::setTrajCmd
bool setTrajCmd(const pr2_msgs::LaserTrajCmd &traj_cmd)
Definition: laser_scanner_traj_controller.cpp:313
controller::LaserScannerTrajController::getCurProfileSegment
int getCurProfileSegment()
Returns the current trajectory segment we're executing in our current profile.
Definition: laser_scanner_traj_controller.cpp:221
controller::LaserScannerTrajController::~LaserScannerTrajController
~LaserScannerTrajController()
Definition: laser_scanner_traj_controller.cpp:53
controller::LaserScannerTrajControllerNode::m_scanner_signal_
pr2_msgs::LaserScannerSignal m_scanner_signal_
Stores the message that we want to send at the end of each sweep, and halfway through each sweep.
Definition: laser_scanner_traj_controller.h:186
pr2_controller_interface::Controller
controller::LaserScannerTrajControllerNode::sub_set_traj_cmd_
ros::Subscriber sub_set_traj_cmd_
Definition: laser_scanner_traj_controller.h:174
controller::LaserScannerTrajController::name_
std::string name_
Definition: laser_scanner_traj_controller.h:165
controller::LaserScannerTrajControllerNode::update
void update()
Definition: laser_scanner_traj_controller.cpp:417
controller::LaserScannerTrajController::getCurProfileTime
double getCurProfileTime()
Returns what time we're currently at in the profile being executed.
Definition: laser_scanner_traj_controller.cpp:208
controller::LaserScannerTrajController::setPeriodicCmd
bool setPeriodicCmd(const pr2_msgs::PeriodicCmd &cmd)
Definition: laser_scanner_traj_controller.cpp:255
tf.h
controller::LaserScannerTrajControllerNode::c_
LaserScannerTrajController c_
Definition: laser_scanner_traj_controller.h:178
controller::LaserScannerTrajController::last_time_
ros::Time last_time_
Definition: laser_scanner_traj_controller.h:177
ros::Time
controller::LaserScannerTrajController::LaserScannerTrajController
LaserScannerTrajController()
Definition: laser_scanner_traj_controller.cpp:47
controller::LaserScannerTrajControllerNode::serve_set_periodic_cmd_
ros::ServiceServer serve_set_periodic_cmd_
Definition: laser_scanner_traj_controller.h:175
controller::LaserScannerTrajControllerNode::service_prefix_
std::string service_prefix_
Definition: laser_scanner_traj_controller.h:180
control_toolbox::Pid
controller::LaserScannerTrajController::traj_command_
double traj_command_
Definition: laser_scanner_traj_controller.h:180
pid.h
controller::LaserScannerTrajControllerNode::robot_
pr2_mechanism_model::RobotState * robot_
Definition: laser_scanner_traj_controller.h:179
controller::LaserScannerTrajControllerNode::setPeriodicCmd
void setPeriodicCmd(const pr2_msgs::PeriodicCmdConstPtr &cmd)
Definition: laser_scanner_traj_controller.cpp:501
filter_chain.hpp
controller::LaserScannerTrajController::update
virtual void update()
Definition: laser_scanner_traj_controller.cpp:135
controller::LaserScannerTrajController::setTrajectory
bool setTrajectory(const std::vector< trajectory::Trajectory::TPoint > &traj_points, double max_rate, double max_acc, std::string interp)
Definition: laser_scanner_traj_controller.cpp:227
controller::LaserScannerTrajControllerNode::serve_set_Traj_cmd_
ros::ServiceServer serve_set_Traj_cmd_
Definition: laser_scanner_traj_controller.h:176
ros::NodeHandle
ros::Subscriber
controller::LaserScannerTrajControllerNode::init
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: laser_scanner_traj_controller.cpp:448
controller::LaserScannerTrajControllerNode::setTrajCmd
void setTrajCmd(const pr2_msgs::LaserTrajCmdConstPtr &traj_cmd)
Definition: laser_scanner_traj_controller.cpp:522
controller::LaserScannerTrajController::tracking_offset_
double tracking_offset_
Definition: laser_scanner_traj_controller.h:179


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Sat Nov 12 2022 03:33:25