123 dbw_mkz_msgs::BrakeCmd
msg;
127 msg.pedal_cmd_type = dbw_mkz_msgs::BrakeCmd::CMD_PERCENT;
134 dbw_mkz_msgs::ThrottleCmd
msg;
138 msg.pedal_cmd_type = dbw_mkz_msgs::ThrottleCmd::CMD_PERCENT;
145 dbw_mkz_msgs::SteeringCmd
msg;
150 msg.cmd_type = dbw_mkz_msgs::SteeringCmd::CMD_ANGLE;
152 float raw_steering_cmd;
156 raw_steering_cmd = 0.5 * dbw_mkz_msgs::SteeringCmd::ANGLE_MAX *
data_.
steering_joy;
163 msg.steering_wheel_angle_velocity =
svel_;
164 msg.steering_wheel_angle_cmd = filtered_steering_cmd;
166 msg.cmd_type = dbw_mkz_msgs::SteeringCmd::CMD_TORQUE;
167 msg.steering_wheel_torque_cmd = dbw_mkz_msgs::SteeringCmd::TORQUE_MAX *
data_.
steering_joy;
175 dbw_mkz_msgs::GearCmd
msg;
183 dbw_mkz_msgs::TurnSignalCmd
msg;
194 ROS_ERROR_THROTTLE(2.0,
"Detected Logitech Gamepad F310 in DirectInput (D) mode. Please select (X) with the switch on the back to select XInput mode.");
243 case dbw_mkz_msgs::TurnSignal::NONE:
250 case dbw_mkz_msgs::TurnSignal::LEFT:
257 case dbw_mkz_msgs::TurnSignal::RIGHT:
269 const std_msgs::Empty empty;
ros::Publisher pub_steering_
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 pub_brake_
#define ROS_ERROR_THROTTLE(rate,...)
JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
ros::Publisher pub_enable_
ros::Publisher pub_disable_
void recvJoy(const sensor_msgs::Joy::ConstPtr &msg)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::Publisher pub_throttle_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void cmdCallback(const ros::TimerEvent &event)
bool getParam(const std::string &key, std::string &s) const
ros::Publisher pub_turn_signal_
float last_steering_filt_output_