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
Boris Bidault committed Aug 20, 2018
2 parents bb8e54d + 8e3dc6e commit b63df21
Show file tree
Hide file tree
Showing 9 changed files with 481 additions and 3 deletions.
79 changes: 79 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,11 @@ target_link_libraries(
oscc_api
)

target_link_libraries(
${PROJECT_NAME}_ros_to_oscc
oscc_api
)

add_dependencies(
${PROJECT_NAME}_ros_to_oscc
${${PROJECT_NAME}_EXPORTED_TARGETS}
Expand Down Expand Up @@ -159,6 +164,80 @@ target_link_libraries(

endif()

if(APOLLO)
if(KIA_SOUL_EV)

find_package(catkin
REQUIRED COMPONENTS
roscpp
rospy
std_msgs
genmsg)

include_directories(include
${catkin_INCLUDE_DIRS}
/apollo/bazel-apollo/bazel-out/local-dbg/genfiles/
)

add_library(
${PROJECT_NAME}_pid_control
src/pid_control.cpp
)


link_directories(
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/canbus/
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/control/
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/localization/
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/common/proto
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/drivers/canbus/common/
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/drivers/canbus/proto/
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/drivers/canbus/ )

add_executable(
${PROJECT_NAME}_apollo
example/${PROJECT_NAME}_apollo.cpp
)

target_include_directories(
${PROJECT_NAME}_apollo PUBLIC
include
)

add_dependencies(
${PROJECT_NAME}_apollo
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
${PROJECT_NAME}_apollo_generate_messages_cpp
)

target_link_libraries(
${PROJECT_NAME}_apollo
${catkin_LIBRARIES}
${PROJECT_NAME}_pid_control
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/canbus/proto/libcanbus_proto_lib.a
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/control/proto/libcontrol_proto_lib.a
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/localization/proto/liblocalization_proto_lib.a
/apollo/bazel-apollo/bazel-out/local-dbg/bin/modules/localization/proto/libpose_proto_lib.a
canbus_proto_lib
protobuf
canbus_lib
control_lib
localization_lib
canbus_common
vehicle_signal_proto_lib
pnc_point_proto_lib
gnss_status_proto_lib
car_sound_proto_lib
header_proto_lib
common_proto_lib
error_code_proto_lib
vehicle_state_proto_lib
)

endif()
endif()

#############
## Testing ##
#############
Expand Down
58 changes: 57 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,62 @@ roslaunch src/roscco/example/example.launch
The roscco_teleop converts the joy messages from the joy_node into messages
for roscco_node and the roscco_node sends it's received messages to OSCC API.

### Apollo open autonomous driving platform

ROSCCO can serve as a bridge to Baidu's open autonomous driving platform Apollo.

This example only support the Kia Soul EV. We are planning on extending support to the Kia Niro.
You will need a double channel Kvaser or two single channel Kvaser, can0 will be drivekit CAN and can1 will be diagnostics CAN.

#### Installation and build

Install and build Apollo

This project was developed on Apollo v2.0.0. It would most probably build on other version of Apollo with some modifications.

```
git clone https://github.com/ApolloAuto/apollo.git --branch v2.0.0
cd apollo/
./docker/scripts/dev_start.sh
./docker/scripts/dev_into.sh
./apollo.sh build
```


Install and build ROSCCO

The installation instructions are very similar to the one above, the main difference is that everything needs to be done within Apollo's docker environment.

```
mkdir -p catkin_ws/src && cd catkin_ws/src
git clone --recursive https://github.com/PolySync/roscco.git
cd ..
catkin_make -DCATKIN_ENABLE_TESTING=0 -DKIA_SOUL_EV=ON -DAPOLLO=ON
source devel/setup.bash
```

#### Running ROSCCO with Apollo

With Apollo control module running,

```
sudo ip link set can0 type can bitrate 500000
sudo ip link set up can0
sudo ip link set can1 type can bitrate 500000
sudo ip link set up can1
roslaunch roscco apollo.launch
```

You can enable OSCC using `rostopic pub`,

```
rostopic pub /enable_disable roscco/EnableDisable "header:
seq: 0
stamp: now
frame_id: ''
enable_control: true"
```


## Running ROSCCO

Expand All @@ -92,7 +148,7 @@ enabling control and turning the steering right with 20% torque:
rostopic pub /enable_disable roscco/EnableDisable -1 \
'{header: {stamp: now}, enable_control: true}'
rostopic pub /SteeringCommand roscco/SteeringCommand -1 \
rostopic pub /steering_command roscco/SteeringCommand -1 \
'{header: {stamp: now}, steering_torque: 0.2}'
```

Expand Down
4 changes: 4 additions & 0 deletions example/apollo.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
<launch>
<node name="roscco_node" pkg="roscco" type="roscco_node" />
<node name="roscco_apollo" pkg="roscco" type="roscco_apollo" />
</launch>
151 changes: 151 additions & 0 deletions example/roscco_apollo.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,151 @@
#include "roscco_apollo.h"


RosccoApollo::RosccoApollo()
{
brake_pub = nh.advertise<roscco::BrakeCommand>( "brake_command", 1 );
throttle_pub = nh.advertise<roscco::ThrottleCommand>( "throttle_command", 1 );
steering_pub = nh.advertise<roscco::SteeringCommand>( "steering_command", 1 );
chassis_pub = nh.advertise<apollo::canbus::Chassis>( "/apollo/canbus/chassis", 1 );

steering_sub = nh.subscribe( "/apollo/control", 1, &RosccoApollo::steeringCallback, this );
brake_sub = nh.subscribe( "/apollo/control", 1, &RosccoApollo::brakeCallback, this );
throttle_sub = nh.subscribe( "/apollo/control", 1, &RosccoApollo::throttleCallback, this );
localization_sub = nh.subscribe( "/apollo/localization/pose", 1, &RosccoApollo::localizationCallback, this );

can_frame_sub = nh.subscribe( "/can_frame", 1, &RosccoApollo::EVCanFrameCallback, this );
}


void RosccoApollo::steeringCallback( const apollo::control::ControlCommand& input )
{
roscco::SteeringCommand output;

output.header.stamp = ros::Time::now();
closedLoopControl( input.steering_target(), output, steering_angle_report );

steering_pub.publish( output );
}


void RosccoApollo::brakeCallback( const apollo::control::ControlCommand& input )
{
roscco::BrakeCommand output;

output.header.stamp = ros::Time::now();
output.brake_position = input.brake() / 100;

brake_pub.publish( output );
}


void RosccoApollo::throttleCallback( const apollo::control::ControlCommand& input )
{
roscco::ThrottleCommand output;

output.header.stamp = ros::Time::now();
output.throttle_position = input.throttle() / 100;

throttle_pub.publish( output );
}


void RosccoApollo::EVCanFrameCallback( const roscco::CanFrame& input )
{
switch( input.frame.can_id )
{
case 512:
{
throttle_report = input.frame.data[4];

throttle_report = throttle_report * THROTTLE_RATIO;

break;
}
case 544:
{
brake_report = input.frame.data[4] + input.frame.data[5] * 256;

brake_report = brake_report * EV_BRAKE_RATIO;

break;
}
case 688:
{
steering_angle_report = input.frame.data[0] + input.frame.data[1] * 256;

if( steering_angle_report > 60000 )
{
steering_angle_report -= 65535;
}

steering_angle_report = steering_angle_report * STEERING_RATIO;

break;
}
case 1200:
{
speed_report = input.frame.data[0] + input.frame.data[2]
+ input.frame.data[4] + input.frame.data[6];

speed_report += ( input.frame.data[1] + input.frame.data[3]
+ input.frame.data[5] + input.frame.data[7] ) * 256;

speed_report = speed_report / 4;

speed_report = speed_report * EV_SPEED_RATIO;

break;
}
default :
{
/// Empty default to leave no untested cases
break;
}
}

apollo::canbus::Chassis output;

output.set_steering_percentage( steering_angle_report );
output.set_throttle_percentage( throttle_report );
output.set_brake_percentage( brake_report );
output.set_speed_mps( speed_report );

chassis_pub.publish( output );
}


void RosccoApollo::localizationCallback( const apollo::localization::LocalizationEstimate& input )
{
std::cout << std::to_string( input.pose().position().x() ) << ", "
<< std::to_string( input.pose().position().y() ) << "\n";
}


void closedLoopControl( double setpoint,
roscco::SteeringCommand& output,
double steering_angle_report )
{
pid_terms params;
pid_state state;

createPIDState( setpoint, &state );

params.max = 1;
params.min = -1;
params.p_term = 0.016;
params.i_term = 0.0001;
params.d_term = 0.01;
params.i_max = 5000;

output.steering_torque = pidController( &params, &state, steering_angle_report );
}


int main( int argc, char** argv )
{
ros::init( argc, argv, "roscco_apollo" );
RosccoApollo roscco_apollo;

ros::spin();
}
Loading

0 comments on commit b63df21

Please sign in to comment.