34 #include <std_msgs/Float64.h> 66 std_msgs::Float64::Ptr erpm_msg(
new std_msgs::Float64);
70 std_msgs::Float64::Ptr servo_msg(
new std_msgs::Float64);
87 ROS_FATAL(
"AckermannToVesc: Parameter %s is required.", name.c_str());
ackermann_msgs::AckermannDriveStamped::ConstPtr AckermannMsgPtr
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())
ros::Publisher servo_pub_
ros::Subscriber ackermann_sub_
void ackermannCmdCallback(const ackermann_msgs::AckermannDriveStamped::ConstPtr &cmd)
double speed_to_erpm_offset_
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
double steering_to_servo_offset_
bool getRequiredParam(const ros::NodeHandle &nh, const std::string &name, T *value)
double speed_to_erpm_gain_
double steering_to_servo_gain_