Skip to content

Commit

Permalink
initial ROS poc wip
Browse files Browse the repository at this point in the history
  • Loading branch information
dehann committed Oct 11, 2019
1 parent 1887cf2 commit 36ed37f
Show file tree
Hide file tree
Showing 3 changed files with 186 additions and 1 deletion.
2 changes: 1 addition & 1 deletion Project.toml
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ CloudGraphs = "≥ 0.1.1"
Combinatorics = "≥ 0.7"
CoordinateTransformations = "≥ 0.5"
DataStructures = "≥ 0.15"
DistributedFactorGraphs = "0.2.2, 0.3"
DistributedFactorGraphs = "0.3, 0.4"
Distributions = "≥ 0.18"
DocStringExtensions = "≥ 0.7"
FFTW = "≥ 0.2.4"
Expand Down
71 changes: 71 additions & 0 deletions examples/ros/ServiceExample.jl
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
# example of ros service in julia

# $ export PYTHON=/usr/bin/python2.7
@assert ENV["PYTHON"]=="/usr/bin/python2.7"
# ]build PyCall

using RobotOS

# standard types
@rosimport geometry_msgs.msg: Point, Pose2D
# bespoke types
@rosimport caesar_ros.srv: AddNode, AddFactor

# generate the types and load
rostypegen()
using .geometry_msgs.msg
using .caesar_ros.srv
# service callbacks
function add_node(req::AddNodeRequest)

reply = AddNodeResponse()
return reply
end

function add_factor(req::AddFactorRequest)

reply = AddFactorResponse()
return reply
end

function callback(msg::Pose2D, pub_obj::Publisher{Point})
pt_msg = Point(msg.x, msg.y, 0.0)
publish(pub_obj, pt_msg)
end

function loop(pub_obj)
loop_rate = Rate(5.0)
while ! is_shutdown()
npt = Point(rand(), rand(), 0.0)
publish(pub_obj, npt)
rossleep(loop_rate)
end
end

function main()
init_node("rosjl_example")
pub = Publisher{Point}("pts", queue_size=10)
sub = Subscriber{Pose2D}("pose", callback, (pub,), queue_size=10)
loop(pub)

add_node_srv = Service('AddNode',caesar_ros.srv.AddNode, addnode)

end

if ! isinteractive()
main()
end













#
114 changes: 114 additions & 0 deletions examples/ros/cpp/example.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
/*
* \file main.cpp
* \author Pedro Vaz Teixeira
* \brief Caesar service server
*/

#include <map>
#include <mutex>

#include <ros/ros.h>

#include <caesar_ros/AddFactor.h>
#include <caesar_ros/AddNode.h>
#include <caesar_ros/GetEstimate.h>

#include <graff/graff.hpp>

namespace {
class Server {
// private:
Server(){}; // can't touch this
public:
Server(const std::string &address, const std::string &session)
: session_(session) {

// setup ROS side: advertise services
add_node_srv_ =
node_handle_.advertiseService("AddNode", &Server::addNode, this);
add_factor_srv_ =
node_handle_.advertiseService("AddFactor", &Server::addFactor, this);
get_estimate_srv_ = node_handle_.advertiseService(
"GetEstimate", &Server::getEstimate, this);

// setup Caesar side
endpoint_.Connect(address);

// TODO: register robot, session
};


// addFactor.srv
// REQUEST:
// string id0
// string id1
// geometry_msgs/PoseWithCovariance measurement
// ---
// REPLY:
// string status
bool addFactor(caesar_ros::AddFactor::Request &req,
caesar_ros::AddFactor::Response &res) {
geometry_msgs::Point zp = req.measurement.pose.position;
geometry_msgs::Quaternion zo = req.measurement.pose.orientation;
std::vector<double> mu = {zp.x, zp.y, zp.z, zo.x, zo.y, zo.z, zo.w};
std::vector<double> cov(req.measurement.covariance.begin(),
req.measurement.covariance.end());
graff::Normal *z = new graff::Normal(mu, cov);

std::vector<std::string> nodes{req.id0, req.id1};
graff::Factor factor("Pose3Pose3", nodes);
factor.push_back(z);
res.status = graff::AddFactor(endpoint_, session_, factor);
return (true);
}


bool addNode(caesar_ros::AddNode::Request &req,
caesar_ros::AddNode::Response &res) {
graff::Variable pose(req.id, "Pose3");
res.status = graff::AddVariable(endpoint_, session_, pose);
return (true);
}


bool getEstimate(caesar_ros::GetEstimate::Request &req,
caesar_ros::GetEstimate::Response &res) {
// retrieve and send estimate from latest solution
auto rep = graff::GetVarMAPMean(endpoint_, session_, req.query);
// TODO: some parsing to fill out response
// (geometry_msgs::PoseWithCovariance)
return (true);
}

void solver(void) {
ros::Rate rate(1);
while (ros::ok()) {
// TODO fetch the latest estimates from the endpoint and cache them
// locally
rate.sleep();
}
}

private:
// ros
ros::NodeHandle node_handle_;
ros::ServiceServer add_factor_srv_, add_node_srv_, get_estimate_srv_;

// caesar
graff::Endpoint endpoint_;
graff::Session session_;
}; // class Server
}; // namespace

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

std::string ep_address("tcp://127.0.0.1:5555"), ep_session("ros-test");
Server caesar_server(ep_address, ep_session );

ros::Rate rate(10);
while (ros::ok()) {
ros::spinOnce();
rate.sleep();
}
}

0 comments on commit 36ed37f

Please sign in to comment.