Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/devel'
Browse files Browse the repository at this point in the history
  • Loading branch information
rebpdx committed Mar 21, 2018
2 parents 2ba0fda + cdfa3c6 commit bb8e54d
Show file tree
Hide file tree
Showing 3 changed files with 42 additions and 48 deletions.
30 changes: 20 additions & 10 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,17 @@ OSCC from their own ROS nodes utilizing ROS messages created from the OSCC API.
ROSCCO is built on the Linux implementation of ROS Kinetic. The only known
limitation for using older versions is that the tests require C++11.

To install ROS Kinetic see the [install instructions](http://wiki.ros.org/kinetic/Installation) on your Linux distribution.
To install ROS Kinetic see the
[install instructions](http://wiki.ros.org/kinetic/Installation) on your Linux
distribution.

### Building ROSCCO in a catkin project

ROSCCO uses the OSCC API which builds for specific vehicle models. OSCC is a
git submodule so that it can be built during the catkin build process.
git submodule so that it can be built during the catkin build process. Make sure
the version of ROSCCO you're using matches with the version of OSCC firmware you
are using. See the [release page](https://github.com/PolySync/roscco/releases)
for information about what releases ROSCCO points to.

```
mkdir -p catkin_ws/src && cd catkin_ws/src
Expand Down Expand Up @@ -49,6 +54,11 @@ To use the example you'll need to bring up a CAN connection for OSCC to
communicate, source the newly compiled package and launch the three nodes,
joy_node, roscco_teleop, and roscco_node.

To install joy node
```
sudo apt-get install ros-kinetic-joy
```

`joy_node` uses `/dev/js0` by default to change this see the
[joystick documentation](http://wiki.ros.org/joy/Tutorials/ConfiguringALinuxJoystick).

Expand All @@ -60,9 +70,8 @@ roslaunch src/roscco/example/example.launch
```

The roscco_teleop converts the joy messages from the joy_node into messages
for roscco_node. The converted messages are sent on a 50ms cadence to ensure
OSCC receives a message within the required OSCC API timing for detection of
lost connection. The roscco_node sends it's received messages to OSCC API.
for roscco_node and the roscco_node sends it's received messages to OSCC API.


## Running ROSCCO

Expand All @@ -78,13 +87,13 @@ rosrun roscco roscco_node _can_channel=0
```

Passing a message through ROS should yield results on your OSCC device such as
enabling control and holding the brake position:
enabling control and turning the steering right with 20% torque:
```
rostopic pub /EnableDisable -1 \
rostopic pub /enable_disable roscco/EnableDisable -1 \
'{header: {stamp: now}, enable_control: true}'
rostopic pub /BrakeCommand roscco/BrakeCommand -r 10 \
'{header: {stamp: now}, brake_position: 50}'
rostopic pub /SteeringCommand roscco/SteeringCommand -1 \
'{header: {stamp: now}, steering_torque: 0.2}'
```

Similarly to the OSCC API, the Reports and CanFrame messages can be
Expand All @@ -99,7 +108,8 @@ ensure OSCC modules do not disable.

## Test Dependencies

ROSCCO requires GoogleTest to be [installed](https://github.com/google/googletest/blob/master/googletest/README.md).
ROSCCO requires GoogleTest to be
[installed](https://github.com/google/googletest/blob/master/googletest/README.md).

ROSCCO also depends on RapidCheck which is included as a submodule, ensure that
the repository has been cloned recursively to include all submodules.
Expand Down
58 changes: 21 additions & 37 deletions example/roscco_teleop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@ class RosccoTeleop

private:
void joystickCallback(const sensor_msgs::Joy::ConstPtr& joy);
void timerCallback(const ros::TimerEvent& event);

ros::NodeHandle nh_;

Expand All @@ -25,7 +24,6 @@ class RosccoTeleop
ros::Publisher steering_pub_;
ros::Publisher enable_disable_pub_;
ros::Subscriber joy_sub_;
ros::Timer timer_;

int previous_start_state_ = 0;
int previous_back_state_ = 0;
Expand Down Expand Up @@ -85,9 +83,6 @@ RosccoTeleop::RosccoTeleop()
steering_pub_ = nh_.advertise<roscco::SteeringCommand>("steering_command", QUEUE_SIZE_);
enable_disable_pub_ = nh_.advertise<roscco::EnableDisable>("enable_disable", QUEUE_SIZE_);

// Timed callback to ensure publishing to OSCC < 200 ms
timer_ = nh_.createTimer(ros::Duration(CALLBACK_FREQ_), &RosccoTeleop::timerCallback, this);

joy_sub_ = nh_.subscribe<sensor_msgs::Joy>("joy", QUEUE_SIZE_, &RosccoTeleop::joystickCallback, this);
}

Expand Down Expand Up @@ -133,6 +128,27 @@ void RosccoTeleop::joystickCallback(const sensor_msgs::Joy::ConstPtr& joy)

previous_back_state_ = joy->buttons[BACK_BUTTON_];
previous_start_state_ = joy->buttons[START_BUTTON_];

if (enabled_)
{
roscco::BrakeCommand brake_msg;
brake_msg.header.stamp = ros::Time::now();
brake_msg.brake_position = brake_;
brake_pub_.publish(brake_msg);

roscco::ThrottleCommand throttle_msg;
throttle_msg.header.stamp = ros::Time::now();
throttle_msg.throttle_position = throttle_;
throttle_pub_.publish(throttle_msg);

// Utilize exponential average similar to OSCC's joystick commander for smoothing of joystick twitchy output
steering_average_ = calc_exponential_average(steering_average_, steering_, DATA_SMOOTHING_FACTOR_);

roscco::SteeringCommand steering_msg;
steering_msg.header.stamp = ros::Time::now();
steering_msg.steering_torque = steering_average_;
steering_pub_.publish(steering_msg);
}
}
else
{
Expand All @@ -154,38 +170,6 @@ void RosccoTeleop::joystickCallback(const sensor_msgs::Joy::ConstPtr& joy)
}
}

/**
* @brief A timer based callback to publish the class variables to OSCC.
*
* This function is a callback for a timer which makes OSCC calls based on the private class variables in order to
* maintain the required publishing frequency for OSCC's disconnection detection mechanism.
*
* @param event The timer event that triggers this callback.
*/
void RosccoTeleop::timerCallback(const ros::TimerEvent& event)
{
if (enabled_)
{
roscco::BrakeCommand brake_msg;
brake_msg.header.stamp = ros::Time::now();
brake_msg.brake_position = brake_;
brake_pub_.publish(brake_msg);

roscco::ThrottleCommand throttle_msg;
throttle_msg.header.stamp = ros::Time::now();
throttle_msg.throttle_position = throttle_;
throttle_pub_.publish(throttle_msg);

// Utilize exponential average similar to OSCC's joystick commander for smoothing of joystick twitchy output
steering_average_ = calc_exponential_average(steering_average_, steering_, DATA_SMOOTHING_FACTOR_);

roscco::SteeringCommand steering_msg;
steering_msg.header.stamp = ros::Time::now();
steering_msg.steering_torque = steering_average_;
steering_pub_.publish(steering_msg);
}
}

/**
* @brief Calculate the exponential average
*
Expand Down
2 changes: 1 addition & 1 deletion oscc
Submodule oscc updated 130 files

0 comments on commit bb8e54d

Please sign in to comment.