100 dbw_pacifica_msgs::AcceleratorPedalCmd accelerator_pedal_msg;
101 accelerator_pedal_msg.enable =
true;
102 accelerator_pedal_msg.ignore =
ignore_;
103 accelerator_pedal_msg.rolling_counter =
counter_;
106 accelerator_pedal_msg.road_slope = 0;
107 accelerator_pedal_msg.control_type.value = dbw_pacifica_msgs::ActuatorControlMode::closed_loop_vehicle;
111 dbw_pacifica_msgs::BrakeCmd brake_msg;
112 brake_msg.enable =
true;
113 brake_msg.rolling_counter =
counter_;
115 brake_msg.control_type.value = dbw_pacifica_msgs::ActuatorControlMode::closed_loop_vehicle;
121 dbw_pacifica_msgs::SteeringCmd steering_msg;
122 steering_msg.enable =
true;
124 steering_msg.rolling_counter =
counter_;
126 steering_msg.angle_velocity =
svel_;
127 steering_msg.control_type.value = dbw_pacifica_msgs::ActuatorControlMode::closed_loop_actuator;
129 steering_msg.angle_cmd *= 0.5;
134 dbw_pacifica_msgs::GearCmd gear_msg;
136 gear_msg.enable =
true;
137 gear_msg.rolling_counter =
counter_;
141 dbw_pacifica_msgs::MiscCmd misc_msg;
143 misc_msg.rolling_counter =
counter_;
146 dbw_pacifica_msgs::GlobalEnableCmd globalEnable_msg;
147 globalEnable_msg.global_enable =
true;
148 globalEnable_msg.enable_joystick_limits =
true;
149 globalEnable_msg.rolling_counter =
counter_;
157 ROS_ERROR(
"Expected %zu joy axis count, received %zu", (
size_t)
AXIS_COUNT, msg->axes.size());
160 if (msg->buttons.size() != (size_t)
BTN_COUNT) {
161 ROS_ERROR(
"Expected %zu joy button count, received %zu", (
size_t)
BTN_COUNT, msg->buttons.size());
209 if (msg->axes[7] !=
joy_.axes[7]) {
211 if (msg->axes[7] < -0.5) {
217 }
else if (msg->axes[7] > 0.5) {
229 case dbw_pacifica_msgs::TurnSignal::NONE:
236 case dbw_pacifica_msgs::TurnSignal::LEFT:
243 case dbw_pacifica_msgs::TurnSignal::RIGHT:
255 const std_msgs::Empty empty;
float accelerator_pedal_joy
ros::Publisher pub_enable_
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())
JoystickDemo(ros::NodeHandle &node, ros::NodeHandle &priv_nh)
ros::Publisher pub_global_enable_
ros::Publisher pub_brake_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
ros::Publisher pub_steering_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool joy_accelerator_pedal_valid
bool getParam(const std::string &key, std::string &s) const
void recvJoy(const sensor_msgs::Joy::ConstPtr &msg)
void cmdCallback(const ros::TimerEvent &event)
ros::Publisher pub_accelerator_pedal_
ros::Publisher pub_disable_