ackermann_to_vesc.cpp
Go to the documentation of this file.
1 // Copyright 2020 F1TENTH Foundation
2 //
3 // Redistribution and use in source and binary forms, with or without modification, are permitted
4 // provided that the following conditions are met:
5 //
6 // 1. Redistributions of source code must retain the above copyright notice, this list of conditions
7 // and the following disclaimer.
8 //
9 // 2. Redistributions in binary form must reproduce the above copyright notice, this list
10 // of conditions and the following disclaimer in the documentation and/or other materials
11 // provided with the distribution.
12 //
13 // 3. Neither the name of the copyright holder nor the names of its contributors may be used
14 // to endorse or promote products derived from this software without specific prior
15 // written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
18 // IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
19 // FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
20 // CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
21 // DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
22 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
23 // WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY
24 // WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 
26 // -*- mode:c++; fill-column: 100; -*-
27 
29 
30 #include <cmath>
31 #include <sstream>
32 #include <string>
33 
34 #include <std_msgs/Float64.h>
35 
36 namespace vesc_ackermann
37 {
38 
39 template <typename T>
40 inline bool getRequiredParam(const ros::NodeHandle& nh, const std::string& name, T* value);
41 
43 {
44  // get conversion parameters
45  if (!getRequiredParam(nh, "speed_to_erpm_gain", &speed_to_erpm_gain_))
46  return;
47  if (!getRequiredParam(nh, "speed_to_erpm_offset", &speed_to_erpm_offset_))
48  return;
49  if (!getRequiredParam(nh, "steering_angle_to_servo_gain", &steering_to_servo_gain_))
50  return;
51  if (!getRequiredParam(nh, "steering_angle_to_servo_offset", &steering_to_servo_offset_))
52  return;
53 
54  // create publishers to vesc electric-RPM (speed) and servo commands
55  erpm_pub_ = nh.advertise<std_msgs::Float64>("commands/motor/speed", 10);
56  servo_pub_ = nh.advertise<std_msgs::Float64>("commands/servo/position", 10);
57 
58  // subscribe to ackermann topic
59  ackermann_sub_ = nh.subscribe("ackermann_cmd", 10, &AckermannToVesc::ackermannCmdCallback, this);
60 }
61 
62 typedef ackermann_msgs::AckermannDriveStamped::ConstPtr AckermannMsgPtr;
63 void AckermannToVesc::ackermannCmdCallback(const AckermannMsgPtr& cmd)
64 {
65  // calc vesc electric RPM (speed)
66  std_msgs::Float64::Ptr erpm_msg(new std_msgs::Float64);
67  erpm_msg->data = speed_to_erpm_gain_ * cmd->drive.speed + speed_to_erpm_offset_;
68 
69  // calc steering angle (servo)
70  std_msgs::Float64::Ptr servo_msg(new std_msgs::Float64);
71  servo_msg->data = steering_to_servo_gain_ * cmd->drive.steering_angle + steering_to_servo_offset_;
72 
73  // publish
74  if (ros::ok())
75  {
76  erpm_pub_.publish(erpm_msg);
77  servo_pub_.publish(servo_msg);
78  }
79 }
80 
81 template <typename T>
82 inline bool getRequiredParam(const ros::NodeHandle& nh, const std::string& name, T* value)
83 {
84  if (nh.getParam(name, *value))
85  return true;
86 
87  ROS_FATAL("AckermannToVesc: Parameter %s is required.", name.c_str());
88  return false;
89 }
90 
91 } // namespace vesc_ackermann
ackermann_msgs::AckermannDriveStamped::ConstPtr AckermannMsgPtr
#define ROS_FATAL(...)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void ackermannCmdCallback(const ackermann_msgs::AckermannDriveStamped::ConstPtr &cmd)
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
AckermannToVesc(ros::NodeHandle nh, ros::NodeHandle private_nh)
bool getParam(const std::string &key, std::string &s) const
bool getRequiredParam(const ros::NodeHandle &nh, const std::string &name, T *value)


vesc_ackermann
Author(s): Michael T. Boulet , Joshua Whitley
autogenerated on Sun Apr 18 2021 02:47:57