99 raptor_dbw_msgs::AcceleratorPedalCmd accelerator_pedal_msg;
100 accelerator_pedal_msg.enable =
true;
101 accelerator_pedal_msg.ignore =
ignore_;
102 accelerator_pedal_msg.rolling_counter =
counter_;
104 accelerator_pedal_msg.control_type.value = raptor_dbw_msgs::ActuatorControlMode::open_loop;
108 raptor_dbw_msgs::BrakeCmd brake_msg;
109 brake_msg.enable =
true;
110 brake_msg.rolling_counter =
counter_;
112 brake_msg.control_type.value = raptor_dbw_msgs::ActuatorControlMode::open_loop;
116 raptor_dbw_msgs::SteeringCmd steering_msg;
117 steering_msg.enable =
true;
119 steering_msg.rolling_counter =
counter_;
121 steering_msg.angle_velocity =
svel_;
122 steering_msg.control_type.value = raptor_dbw_msgs::ActuatorControlMode::closed_loop_actuator;
124 steering_msg.angle_cmd *= 0.5;
129 raptor_dbw_msgs::GearCmd gear_msg;
131 gear_msg.enable =
true;
132 gear_msg.rolling_counter =
counter_;
136 raptor_dbw_msgs::MiscCmd misc_msg;
138 misc_msg.rolling_counter =
counter_;
141 raptor_dbw_msgs::GlobalEnableCmd globalEnable_msg;
142 globalEnable_msg.global_enable =
true;
143 globalEnable_msg.enable_joystick_limits =
true;
144 globalEnable_msg.rolling_counter =
counter_;
152 ROS_ERROR(
"Expected %zu joy axis count, received %zu", (
size_t)
AXIS_COUNT, msg->axes.size());
155 if (msg->buttons.size() != (size_t)
BTN_COUNT) {
156 ROS_ERROR(
"Expected %zu joy button count, received %zu", (
size_t)
BTN_COUNT, msg->buttons.size());
198 case raptor_dbw_msgs::TurnSignal::NONE:
205 case raptor_dbw_msgs::TurnSignal::LEFT:
212 case raptor_dbw_msgs::TurnSignal::RIGHT:
224 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_