caster_controller.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Stuart Glaser
32  */
33 
36 
38 
39 namespace controller {
40 
41 const double CasterController::WHEEL_RADIUS = 0.079;
42 const double CasterController::WHEEL_OFFSET = 0.049;
43 
44 CasterController::CasterController()
45  : steer_velocity_(0), drive_velocity_(0)
46 {
47 }
48 
50 {
51 }
52 
55  const std::string &caster_joint,
56  const std::string &wheel_l_joint, const std::string &wheel_r_joint,
57  const control_toolbox::Pid &caster_pid, const control_toolbox::Pid &wheel_pid)
58 {
59  caster_ = robot->getJointState(caster_joint);
60  if (!caster_)
61  {
62  fprintf(stderr, "Error: Caster joint \"%s\" does not exist\n", caster_joint.c_str());
63  return false;
64  }
65 
66  if (!caster_vel_.init(robot, caster_joint, caster_pid))
67  return false;
68  if (!wheel_l_vel_.init(robot, wheel_l_joint, wheel_pid))
69  return false;
70  if (!wheel_r_vel_.init(robot, wheel_r_joint, wheel_pid))
71  return false;
72 
73  return true;
74 }
75 
77 {
78  node_ = n;
79  assert(robot);
80 
81  // Reads in the joints to control
82 
83  std::string caster_joint_name, wheel_l_joint_name, wheel_r_joint_name;
84  if (!node_.getParam("joints/caster", caster_joint_name))
85  {
86  ROS_ERROR("No caster joint given (namespace: %s)", node_.getNamespace().c_str());
87  return false;
88  }
89  if (!node_.getParam("joints/wheel_l", wheel_l_joint_name))
90  {
91  ROS_ERROR("No wheel_l joint given (namespace: %s)", node_.getNamespace().c_str());
92  return false;
93  }
94  if (!node_.getParam("joints/wheel_r", wheel_r_joint_name))
95  {
96  ROS_ERROR("No wheel_r joint given (namespace: %s)", node_.getNamespace().c_str());
97  return false;
98  }
99  if (!(caster_ = robot->getJointState(caster_joint_name)))
100  {
101  ROS_ERROR("Caster joint \"%s\" does not exist (namespace: %s)",
102  caster_joint_name.c_str(), node_.getNamespace().c_str());
103  return false;
104  }
105 
106  // Prepares the namespaces for the velocity controllers
107 
108  XmlRpc::XmlRpcValue caster_pid, wheel_pid;
109  node_.getParam("caster_pid", caster_pid);
110  node_.getParam("wheel_pid", wheel_pid);
111 
113  caster_node(n, "caster"),
114  wheel_l_node(n, "wheel_l"),
115  wheel_r_node(n, "wheel_r");
116 
117  caster_node.setParam("type", std::string("JointVelocityController"));
118  caster_node.setParam("joint", caster_joint_name);
119  caster_node.setParam("pid", caster_pid);
120 
121  wheel_l_node.setParam("type", std::string("JointVelocityController"));
122  wheel_l_node.setParam("joint", wheel_l_joint_name);
123  wheel_l_node.setParam("pid", wheel_pid);
124 
125  wheel_r_node.setParam("type", std::string("JointVelocityController"));
126  wheel_r_node.setParam("joint", wheel_r_joint_name);
127  wheel_r_node.setParam("pid", wheel_pid);
128 
129  assert(robot);
130  if (!caster_vel_.init(robot, caster_node)) return false;
131  if (!wheel_l_vel_.init(robot, wheel_l_node)) return false;
132  if (!wheel_r_vel_.init(robot, wheel_r_node)) return false;
133 
134  steer_cmd_ = node_.subscribe<std_msgs::Float64>("steer", 1, &CasterController::setSteerCB, this);
135  drive_cmd_ = node_.subscribe<std_msgs::Float64>("drive", 1, &CasterController::setDriveCB, this);
136 
137  return true;
138 }
139 
141 {
143 
144  double wd = drive_velocity_ / WHEEL_RADIUS; // Angular velocity due to driving
145  double ws = (WHEEL_OFFSET / WHEEL_RADIUS) * steer_velocity_; // Angular velocity due to steering
146  wheel_r_vel_.setCommand(wd + ws);
147  wheel_l_vel_.setCommand(wd - ws);
148 
152 }
153 
154 void CasterController::setSteerCB(const std_msgs::Float64ConstPtr& msg)
155 {
156  steer_velocity_ = msg->data;
157 }
158 
159 void CasterController::setDriveCB(const std_msgs::Float64ConstPtr& msg)
160 {
161  drive_velocity_ = msg->data;
162 }
163 
164 
165 
166 }
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
static const double WHEEL_OFFSET
JointVelocityController caster_vel_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
pr2_mechanism_model::JointState * caster_
JointVelocityController wheel_r_vel_
void setSteerCB(const std_msgs::Float64ConstPtr &msg)
JointVelocityController wheel_l_vel_
void setDriveCB(const std_msgs::Float64ConstPtr &msg)
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
bool init(pr2_mechanism_model::RobotState *robot_state, const std::string &caster_joint, const std::string &wheel_l_joint, const std::string &wheel_r_joint, const control_toolbox::Pid &caster_pid, const control_toolbox::Pid &wheel_pid)
static const double WHEEL_RADIUS
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)


pr2_mechanism_controllers
Author(s): Sachin Chita, John Hsu, Melonee Wise
autogenerated on Wed Jun 5 2019 19:34:08