Skip to content

Commit

Permalink
add messages for shutdown, recording and auto navigation
Browse files Browse the repository at this point in the history
  • Loading branch information
tevenfeng committed Oct 24, 2018
1 parent 0aa5d3b commit 76ee471
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 24 deletions.
6 changes: 3 additions & 3 deletions tju_car/include/tju_car/tju_car.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,11 @@ class TjuCar
// max linear velocity and max angular velocity
double MAX_LINEAR_VEL, MAX_ANGULAR_VEL;

int axisAngular,axisLinear, brakeButton, startButton, startRecordButton, stopRecordButton, startRosbagButton, stopRosbagButton, startNavigationButton, stopNavigationButton;
int axisAngular,axisLinear, brakeButton, startButton, startRecordButton, stopRecordButton, startNavigationButton, stopNavigationButton;

int brakeButtonValue, startButtonValue, startRecordButtonValue, stopRecordButtonValue, startRosbagButtonValue, stopRosbagButtonValue, startNavigationButtonValue, stopNavigationButtonValue;
int brakeButtonValue, startButtonValue, startRecordButtonValue, stopRecordButtonValue, startNavigationButtonValue, stopNavigationButtonValue;

bool isShutdown, isRecording, isRecordingRosbag, isNavigating;
bool isShutdown, isRecording, isNavigating;

void convert2send(geometry_msgs::Twist v, char send_buf[]);
};
Expand Down
25 changes: 4 additions & 21 deletions tju_car/src/tju_car.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,6 @@ TjuCar::TjuCar()
// Receive stop recording button
n.param<int>("stop_recording_button", stopRecordButton, 2);

// Receive start recording rosbag button
n.param<int>("start_rosbag_button", startRosbagButton, 0);

// Receive stop recording rosbag button
n.param<int>("stop_rosbag_button", stopRosbagButton, 3);

// Receive stop navigation button
n.param<int>("stop_navigation_button", stopNavigationButton, 8);

Expand Down Expand Up @@ -70,10 +64,12 @@ void TjuCar::joy_callback(const sensor_msgs::Joy::ConstPtr& Joy)
brakeButtonValue = Joy->buttons[brakeButton];
if(brakeButtonValue && !isShutdown){
isShutdown = true;
ROS_INFO("EMERGENCY Shutdown START!");
}
startButtonValue = Joy->buttons[startButton];
if(startButtonValue && isShutdown){
isShutdown = false;
ROS_INFO("EMERGENCY Shutdown END!");
}

// Determine whether we should be recording data
Expand All @@ -92,25 +88,12 @@ void TjuCar::joy_callback(const sensor_msgs::Joy::ConstPtr& Joy)
startNavigationButtonValue = Joy->buttons[startNavigationButton];
if(startNavigationButtonValue && !isNavigating){
isNavigating = true;
ROS_INFO("Start Auto Navigation!");
}
stopNavigationButtonValue = Joy->buttons[stopNavigationButton];
if(stopNavigationButtonValue && isNavigating){
isNavigating = false;
}

// Determine whether we should be recording rosbag
// If isRecordingRosbag==true then we shall be recording all data into rosbag files
startRosbagButtonValue = Joy->buttons[startRosbagButton];
if(startRosbagButtonValue && !isRecordingRosbag){
isRecordingRosbag = true;
//system("/home/nvidia/AutonomousTju/src/tju_car/scripts/record_rosbag.sh");
ROS_INFO("Start Recording Rosbag!");
}
stopRosbagButtonValue = Joy->buttons[stopRosbagButton];
if(stopRosbagButtonValue && isRecordingRosbag){
isRecordingRosbag = false;
//system("/home/nvidia/AutonomousTju/src/tju_car/scripts/record_rosbag.sh");
ROS_INFO("Stop Recording! Rosbag");
ROS_INFO("Stop Auto Navigation!");
}

pthread_mutex_lock(&mutex);
Expand Down

0 comments on commit 76ee471

Please sign in to comment.