publish_control_board_rev3.h
Go to the documentation of this file.
00001 /*
00002 * Unpublished Copyright (c) 2009-2018 AutonomouStuff, LLC, All Rights Reserved.
00003 *
00004 * This file is part of the PACMod ROS 1.0 driver which is released under the MIT license.
00005 * See file LICENSE included with this software or go to https://opensource.org/licenses/MIT for full license details.
00006 */
00007  
00008 #ifndef PUBLISH_CONTROL_BOARD_REV3_H
00009 #define PUBLISH_CONTROL_BOARD_REV3_H
00010 
00011 #include "globals.h"
00012 #include "publish_control.h"
00013 
00014 #include <pacmod_msgs/SteerSystemCmd.h>
00015 #include <pacmod_msgs/SystemCmdBool.h>
00016 #include <pacmod_msgs/SystemCmdFloat.h>
00017 #include <pacmod_msgs/SystemCmdInt.h>
00018 #include <pacmod_msgs/SystemRptInt.h>
00019 
00020 namespace AS
00021 {
00022 namespace Joystick
00023 {
00024 
00025 class PublishControlBoardRev3 :
00026   public PublishControl
00027 {
00028   public:
00029     PublishControlBoardRev3();
00030     static void callback_shift_rpt(const pacmod_msgs::SystemRptInt::ConstPtr& msg);
00031     static void callback_turn_rpt(const pacmod_msgs::SystemRptInt::ConstPtr& msg);
00032 
00033     // Variables
00034     static int last_shift_cmd;
00035     static int last_turn_cmd;
00036     static float last_brake_cmd;
00037 
00038   private:
00039     // private functions
00040     void publish_steering_message(const sensor_msgs::Joy::ConstPtr& msg);
00041     void publish_turn_signal_message(const sensor_msgs::Joy::ConstPtr& msg);
00042     void publish_shifting_message(const sensor_msgs::Joy::ConstPtr& msg);
00043     void publish_accelerator_message(const sensor_msgs::Joy::ConstPtr& msg);
00044     void publish_brake_message(const sensor_msgs::Joy::ConstPtr& msg);
00045     void publish_lights_horn_wipers_message(const sensor_msgs::Joy::ConstPtr& msg);
00046 
00047     // ROS Subscribers
00048     ros::Subscriber shift_sub;
00049     ros::Subscriber turn_sub;
00050 };
00051 
00052 }
00053 }
00054 
00055 #endif


pacmod_game_control
Author(s): Joe Driscoll
autogenerated on Thu Jun 6 2019 21:10:24